Merge "Added Restart All command"
diff --git a/aos/actions/BUILD b/aos/actions/BUILD
index 5cc7e58..d5920fd 100644
--- a/aos/actions/BUILD
+++ b/aos/actions/BUILD
@@ -16,7 +16,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":actions_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//aos/time",
         "//aos/util:phased_loop",
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index 3cc4d9e..0478d9a 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -1,14 +1,14 @@
 #ifndef AOS_ACTIONS_ACTOR_H_
 #define AOS_ACTIONS_ACTOR_H_
 
-#include <stdio.h>
 #include <inttypes.h>
+#include <stdio.h>
 
 #include <chrono>
 #include <functional>
 
 #include "aos/actions/actions_generated.h"
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/logging/logging.h"
 #include "aos/time/time.h"
 #include "aos/util/phased_loop.h"
@@ -76,7 +76,7 @@
   // Done condition are defined as functions that return true when done
   // end_time is when to stop and return true. Time(0, 0) (the default) means
   // never time out.
-  // This will be polled at ::aos::controls::kLoopFrequency
+  // This will be polled at ::frc971::controls::kLoopFrequency
   bool WaitUntil(::std::function<bool(void)> done_condition,
                  ::aos::monotonic_clock::time_point end_time =
                      ::aos::monotonic_clock::min_time);
@@ -184,7 +184,7 @@
 template <class T>
 bool ActorBase<T>::WaitUntil(::std::function<bool(void)> done_condition,
                              ::aos::monotonic_clock::time_point end_time) {
-  ::aos::time::PhasedLoop phased_loop(::aos::controls::kLoopFrequency,
+  ::aos::time::PhasedLoop phased_loop(::frc971::controls::kLoopFrequency,
                                       event_loop_->monotonic_now(),
                                       ::std::chrono::milliseconds(5) / 2);
 
diff --git a/aos/controls/BUILD b/aos/controls/BUILD
deleted file mode 100644
index 027b8ca..0000000
--- a/aos/controls/BUILD
+++ /dev/null
@@ -1,115 +0,0 @@
-package(default_visibility = ["//visibility:public"])
-
-load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
-
-cc_library(
-    name = "control_loop_test",
-    testonly = True,
-    srcs = [
-        "control_loop_test.cc",
-    ],
-    hdrs = [
-        "control_loop_test.h",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        "//aos:flatbuffers",
-        "//aos:json_to_flatbuffer",
-        "//aos/events:simulated_event_loop",
-        "//frc971/input:joystick_state_fbs",
-        "//frc971/input:robot_state_fbs",
-        "//aos/testing:googletest",
-        "//aos/testing:test_logging",
-        "//aos/time",
-    ],
-)
-
-cc_library(
-    name = "polytope",
-    hdrs = [
-        "polytope.h",
-    ],
-    deps = [
-        "@org_tuxfamily_eigen//:eigen",
-    ] + select({
-        "@platforms//os:linux": [
-            "//aos/logging",
-            "//third_party/cddlib",
-            "@com_github_google_glog//:glog",
-        ],
-        "//conditions:default": [],
-    }),
-)
-
-cc_test(
-    name = "polytope_test",
-    srcs = [
-        "polytope_test.cc",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        ":polytope",
-        "//aos/testing:googletest",
-        "//aos/testing:test_logging",
-        "@org_tuxfamily_eigen//:eigen",
-    ],
-)
-
-flatbuffer_cc_library(
-    name = "control_loop_fbs",
-    srcs = [
-        "control_loops.fbs",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-)
-
-cc_library(
-    name = "control_loop",
-    srcs = [
-        "control_loop.cc",
-        "control_loop-tmpl.h",
-    ],
-    hdrs = [
-        "control_loop.h",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        "//aos/events:event_loop",
-        "//aos/events:shm_event_loop",
-        "//aos/logging",
-        "//frc971/input:joystick_state_fbs",
-        "//frc971/input:robot_state_fbs",
-        "//aos/time",
-        "//aos/util:log_interval",
-    ],
-)
-
-cc_library(
-    name = "quaternion_utils",
-    srcs = [
-        "quaternion_utils.cc",
-    ],
-    hdrs = [
-        "quaternion_utils.h",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        "@com_github_google_glog//:glog",
-        "@org_tuxfamily_eigen//:eigen",
-    ],
-)
-
-cc_test(
-    name = "quarternion_utils_test",
-    srcs = [
-        "quaternion_utils_test.cc",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        ":quaternion_utils",
-        "//aos/testing:googletest",
-        "//aos/testing:random_seed",
-        "@com_github_google_glog//:glog",
-        "@org_tuxfamily_eigen//:eigen",
-    ],
-)
diff --git a/aos/controls/control_loop.cc b/aos/controls/control_loop.cc
deleted file mode 100644
index 17e5d7e..0000000
--- a/aos/controls/control_loop.cc
+++ /dev/null
@@ -1,7 +0,0 @@
-#include "aos/controls/control_loop.h"
-
-namespace aos {
-namespace controls {
-
-}  // namespace controls
-}  // namespace aos
diff --git a/aos/controls/control_loop_test.cc b/aos/controls/control_loop_test.cc
deleted file mode 100644
index 8a21f1f..0000000
--- a/aos/controls/control_loop_test.cc
+++ /dev/null
@@ -1,10 +0,0 @@
-#include "aos/controls/control_loop_test.h"
-
-#include <chrono>
-
-namespace aos {
-namespace testing {
-
-
-}  // namespace testing
-}  // namespace aos
diff --git a/aos/events/logging/log_cat.cc b/aos/events/logging/log_cat.cc
index 3469674..c2378ab 100644
--- a/aos/events/logging/log_cat.cc
+++ b/aos/events/logging/log_cat.cc
@@ -36,6 +36,8 @@
 DEFINE_bool(print, true,
             "If true, actually print the messages.  If false, discard them, "
             "confirming they can be parsed.");
+DEFINE_bool(print_parts_only, false,
+            "If true, only print out the results of logfile sorting.");
 
 // Print the flatbuffer out to stdout, both to remove the unnecessary cruft from
 // glog and to allow the user to readily redirect just the logged output
@@ -95,6 +97,12 @@
     const aos::logger::LogFileHeader *full_header = reader.log_file_header();
     if (!FLAGS_raw_header.empty()) {
       raw_header_reader.emplace(FLAGS_raw_header);
+      std::cout << aos::FlatbufferToJson(
+                       reader.log_file_header(),
+                       {.multi_line = FLAGS_pretty,
+                        .max_vector_size =
+                            static_cast<size_t>(FLAGS_max_vector_size)})
+                << std::endl;
       CHECK_EQ(
           reader.log_file_header()->configuration_sha256()->string_view(),
           aos::logger::Sha256(raw_header_reader->raw_log_file_header().span()));
@@ -165,6 +173,12 @@
 
   for (auto &it : logfiles) {
     VLOG(1) << it;
+    if (FLAGS_print_parts_only) {
+      std::cout << it << std::endl;
+    }
+  }
+  if (FLAGS_print_parts_only) {
+    return 0;
   }
 
   aos::logger::LogReader reader(logfiles);
diff --git a/aos/events/logging/logfile_sorting.cc b/aos/events/logging/logfile_sorting.cc
index 80d909b..2db9230 100644
--- a/aos/events/logging/logfile_sorting.cc
+++ b/aos/events/logging/logfile_sorting.cc
@@ -100,77 +100,107 @@
   return found_logfiles;
 }
 
-std::vector<LogFile> SortParts(const std::vector<std::string> &parts) {
+// Start by grouping all parts by UUID, and extracting the part index.
+// Datastructure to hold all the info extracted from a set of parts which go
+// together so we can sort them afterwords.
+struct UnsortedLogParts {
+  // Start times.
+  aos::monotonic_clock::time_point monotonic_start_time;
+  aos::realtime_clock::time_point realtime_start_time;
+
+  aos::monotonic_clock::time_point logger_monotonic_start_time =
+      aos::monotonic_clock::min_time;
+  aos::realtime_clock::time_point logger_realtime_start_time =
+      aos::realtime_clock::min_time;
+
+  // Node to save.
+  std::string node;
+
+  // The boot UUID of the node which generated this data.
+  std::string source_boot_uuid;
+
+  // Pairs of the filename and the part index for sorting.
+  std::vector<std::pair<std::string, int>> parts;
+
+  std::string config_sha256;
+};
+
+// Struct to hold both the node, and the parts associated with it.
+struct UnsortedLogPartsMap {
+  std::string logger_node;
+  // The boot UUID of the node this log file was created on.
+  std::string logger_boot_uuid;
+
+  aos::monotonic_clock::time_point monotonic_start_time =
+      aos::monotonic_clock::min_time;
+  aos::realtime_clock::time_point realtime_start_time =
+      aos::realtime_clock::min_time;
+
+  // Name from a log.  All logs below have been confirmed to match.
+  std::string name;
+
+  std::map<std::string, UnsortedLogParts> unsorted_parts;
+};
+
+// Sort part files without UUIDs and part indexes as well.  Extract everything
+// useful from the log in the first pass, then sort later.
+struct UnsortedOldParts {
+  // Part information with everything but the list of parts.
+  LogParts parts;
+
+  // Tuple of time for the data and filename needed for sorting after
+  // extracting.
+  std::vector<std::pair<monotonic_clock::time_point, std::string>>
+      unsorted_parts;
+
+  // Name from a log.  All logs below have been confirmed to match.
+  std::string name;
+};
+
+struct NodeBootState {
+  // Maps each boot to its constraining boots. If the bool in the value is true,
+  // then the boot uuid in the key chronologically precedes the boot uuid in
+  // the value, and vice versa if false.
+  std::map<std::string, std::vector<std::pair<std::string, bool>>> constraints;
+
+  // All the boots we know about.
+  std::set<std::string> boots;
+};
+
+// Helper class to make it easier to sort a list of log files into
+// std::vector<LogFile>
+struct PartsSorter {
+  // List of files that were corrupted.
   std::vector<std::string> corrupted;
 
+  // Map from sha256 to the config.
   std::map<std::string, std::shared_ptr<const Configuration>>
       config_sha256_lookup;
 
-  // Start by grouping all parts by UUID, and extracting the part index.
-  // Datastructure to hold all the info extracted from a set of parts which go
-  // together so we can sort them afterwords.
-  struct UnsortedLogParts {
-    // Start times.
-    aos::monotonic_clock::time_point monotonic_start_time;
-    aos::realtime_clock::time_point realtime_start_time;
-
-    aos::monotonic_clock::time_point logger_monotonic_start_time =
-        aos::monotonic_clock::min_time;
-    aos::realtime_clock::time_point logger_realtime_start_time =
-        aos::realtime_clock::min_time;
-
-    // Node to save.
-    std::string node;
-
-    // The boot UUID of the node which generated this data.
-    std::string source_boot_uuid;
-
-    // Pairs of the filename and the part index for sorting.
-    std::vector<std::pair<std::string, int>> parts;
-
-    std::string config_sha256;
-  };
-
-  // Struct to hold both the node, and the parts associated with it.
-  struct UnsortedLogPartsMap {
-    std::string logger_node;
-    // The boot UUID of the node this log file was created on.
-    std::string logger_boot_uuid;
-
-    aos::monotonic_clock::time_point monotonic_start_time =
-        aos::monotonic_clock::min_time;
-    aos::realtime_clock::time_point realtime_start_time =
-        aos::realtime_clock::min_time;
-
-    // Name from a log.  All logs below have been confirmed to match.
-    std::string name;
-
-    std::map<std::string, UnsortedLogParts> unsorted_parts;
-  };
-
   // Map holding the log_event_uuid -> second map.  The second map holds the
   // parts_uuid -> list of parts for sorting.
   std::map<std::string, UnsortedLogPartsMap> parts_list;
 
-  // Sort part files without UUIDs and part indexes as well.  Extract everything
-  // useful from the log in the first pass, then sort later.
-  struct UnsortedOldParts {
-    // Part information with everything but the list of parts.
-    LogParts parts;
-
-    // Tuple of time for the data and filename needed for sorting after
-    // extracting.
-    std::vector<std::pair<monotonic_clock::time_point, std::string>>
-        unsorted_parts;
-
-    // Name from a log.  All logs below have been confirmed to match.
-    std::string name;
-  };
-
   // A list of all the old parts which we don't know how to sort using uuids.
   // There are enough of these in the wild that this is worth supporting.
   std::vector<UnsortedOldParts> old_parts;
 
+  // Populates the class's datastructures from the input file list.
+  void PopulateFromFiles(const std::vector<std::string> &parts);
+
+  // Wrangle parts_list into a map of boot uuids -> boot counts.
+  std::map<std::string, int> ComputeBootCounts();
+
+  // Reformats old_parts into a list of logfiles and returns it.  This destroys
+  // state in PartsSorter.
+  std::vector<LogFile> FormatOldParts();
+
+  // Reformats parts_list into a list of logfiles and returns it.  This destroys
+  // state in PartsSorter.
+  std::vector<LogFile> FormatNewParts();
+};
+
+void PartsSorter::PopulateFromFiles(const std::vector<std::string> &parts) {
   // Now extract everything into our datastructures above for sorting.
   for (const std::string &part : parts) {
     std::optional<SizePrefixedFlatbufferVector<LogFileHeader>> log_header =
@@ -237,9 +267,11 @@
     }
 
     if (configuration_sha256.empty()) {
-      CHECK(log_header->message().has_configuration());
+      CHECK(log_header->message().has_configuration())
+          << ": Failed to find header on " << part;
     } else {
-      CHECK(!log_header->message().has_configuration());
+      CHECK(!log_header->message().has_configuration())
+          << ": Found header where one shouldn't be on " << part;
     }
 
     // Looks like an old log.  No UUID, index, and also single node.  We have
@@ -356,79 +388,350 @@
 
     it->second.parts.emplace_back(std::make_pair(part, parts_index));
   }
+}
 
-  if (old_parts.empty() && parts_list.empty()) {
-    if (parts.empty()) {
-      return std::vector<LogFile>{};
-    } else {
-      LogFile log_file;
-      log_file.corrupted = std::move(corrupted);
-      return std::vector<LogFile>{log_file};
-    }
-  }
-  CHECK_NE(old_parts.empty(), parts_list.empty())
-      << ": Can't have a mix of old and new parts.";
-
+std::vector<LogFile> PartsSorter::FormatOldParts() {
   // Now reformat old_parts to be in the right datastructure to report.
   std::map<std::string, std::shared_ptr<const Configuration>>
       copied_config_sha256;
-  if (!old_parts.empty()) {
-    std::vector<LogFile> result;
-    for (UnsortedOldParts &p : old_parts) {
-      // Sort by the oldest message in each file.
-      std::sort(
-          p.unsorted_parts.begin(), p.unsorted_parts.end(),
-          [](const std::pair<monotonic_clock::time_point, std::string> &a,
-             const std::pair<monotonic_clock::time_point, std::string> &b) {
-            return a.first < b.first;
-          });
-      LogFile log_file;
+  CHECK(!old_parts.empty());
 
-      // We want to use a single Configuration flatbuffer for all the parts to
-      // make downstream easier.  Since this is an old log, it doesn't have a
-      // SHA256 in the header to rely on, so we need a way to detect duplicates.
-      //
-      // SHA256 is decently fast, so use that as a representative hash of the
-      // header.
-      auto header =
-          std::make_shared<SizePrefixedFlatbufferVector<LogFileHeader>>(
-              std::move(*ReadHeader(p.unsorted_parts[0].second)));
+  std::vector<LogFile> result;
+  for (UnsortedOldParts &p : old_parts) {
+    // Sort by the oldest message in each file.
+    std::sort(p.unsorted_parts.begin(), p.unsorted_parts.end(),
+              [](const std::pair<monotonic_clock::time_point, std::string> &a,
+                 const std::pair<monotonic_clock::time_point, std::string> &b) {
+                return a.first < b.first;
+              });
+    LogFile log_file;
 
-      // Do a recursive copy to normalize the flatbuffer.  Different
-      // configurations can be built different ways, and can even have their
-      // vtable out of order.  Don't think and just trigger a copy.
-      FlatbufferDetachedBuffer<Configuration> config_copy =
-          RecursiveCopyFlatBuffer(header->message().configuration());
+    // We want to use a single Configuration flatbuffer for all the parts to
+    // make downstream easier.  Since this is an old log, it doesn't have a
+    // SHA256 in the header to rely on, so we need a way to detect duplicates.
+    //
+    // SHA256 is decently fast, so use that as a representative hash of the
+    // header.
+    auto header = std::make_shared<SizePrefixedFlatbufferVector<LogFileHeader>>(
+        std::move(*ReadHeader(p.unsorted_parts[0].second)));
 
-      std::string config_copy_sha256 = Sha256(config_copy.span());
+    // Do a recursive copy to normalize the flatbuffer.  Different
+    // configurations can be built different ways, and can even have their
+    // vtable out of order.  Don't think and just trigger a copy.
+    FlatbufferDetachedBuffer<Configuration> config_copy =
+        RecursiveCopyFlatBuffer(header->message().configuration());
 
-      auto it = copied_config_sha256.find(config_copy_sha256);
-      if (it != copied_config_sha256.end()) {
-        log_file.config = it->second;
-      } else {
-        std::shared_ptr<const Configuration> config(
-            header, header->message().configuration());
+    std::string config_copy_sha256 = Sha256(config_copy.span());
 
-        copied_config_sha256.emplace(std::move(config_copy_sha256), config);
-        log_file.config = config;
-      }
+    auto it = copied_config_sha256.find(config_copy_sha256);
+    if (it != copied_config_sha256.end()) {
+      log_file.config = it->second;
+    } else {
+      std::shared_ptr<const Configuration> config(
+          header, header->message().configuration());
 
-      for (std::pair<monotonic_clock::time_point, std::string> &f :
-           p.unsorted_parts) {
-        p.parts.parts.emplace_back(std::move(f.second));
-      }
-      p.parts.config = log_file.config;
-      log_file.parts.emplace_back(std::move(p.parts));
-      log_file.monotonic_start_time = log_file.parts[0].monotonic_start_time;
-      log_file.realtime_start_time = log_file.parts[0].realtime_start_time;
-      log_file.corrupted = corrupted;
-      log_file.name = p.name;
-      result.emplace_back(std::move(log_file));
+      copied_config_sha256.emplace(std::move(config_copy_sha256), config);
+      log_file.config = config;
     }
 
-    return result;
+    for (std::pair<monotonic_clock::time_point, std::string> &f :
+         p.unsorted_parts) {
+      p.parts.parts.emplace_back(std::move(f.second));
+    }
+    p.parts.config = log_file.config;
+    log_file.parts.emplace_back(std::move(p.parts));
+    log_file.monotonic_start_time = log_file.parts[0].monotonic_start_time;
+    log_file.realtime_start_time = log_file.parts[0].realtime_start_time;
+    log_file.corrupted = corrupted;
+    log_file.name = p.name;
+    result.emplace_back(std::move(log_file));
   }
 
+  return result;
+}
+
+std::map<std::string, int> PartsSorter::ComputeBootCounts() {
+  std::map<std::string, NodeBootState> boot_constraints;
+
+  // TODO(austin): This is the "old" way.  Once we have better ordering info in
+  // headers, we should use it.
+  for (std::pair<const std::string, UnsortedLogPartsMap> &logs : parts_list) {
+    {
+      // We know nothing about the order of the logger node's boot, but we know
+      // it happened.  If there is only 1 single boot, the constraint code will
+      // happily mark it as boot 0.  Otherwise we'll get the appropriate boot
+      // count if it can be computed or an error.
+      //
+      // Add it to the boots list to kick this off.
+      auto it = boot_constraints.find(logs.second.logger_node);
+      if (it == boot_constraints.end()) {
+        it = boot_constraints
+                 .insert(
+                     std::make_pair(logs.second.logger_node, NodeBootState()))
+                 .first;
+      }
+
+      it->second.boots.insert(logs.second.logger_boot_uuid);
+    }
+
+    std::map<std::string,
+             std::vector<std::pair<std::string, std::pair<int, int>>>>
+        node_boot_parts_index_ranges;
+
+    for (std::pair<const std::string, UnsortedLogParts> &parts :
+         logs.second.unsorted_parts) {
+      CHECK_GT(parts.second.parts.size(), 0u);
+
+      // Track that this boot exists so we know the overall set of boots we need
+      // to link.
+      {
+        auto node_boot_constraints_it =
+            boot_constraints.find(parts.second.node);
+        if (node_boot_constraints_it == boot_constraints.end()) {
+          node_boot_constraints_it =
+              boot_constraints
+                  .insert(std::make_pair(parts.second.node, NodeBootState()))
+                  .first;
+        }
+        node_boot_constraints_it->second.boots.insert(
+            parts.second.source_boot_uuid);
+      }
+
+      // Since the logger node is guarenteed to be on a single boot, we can look
+      // for reboots on the remote nodes and use the parts_index to track when
+      // they reboot.
+      //
+      // All the parts files rotate at the same time, so the parts_index will
+      // match.  We can track the min and max parts_index for a
+      // source_node_boot_uuid and use that to order the boot uuids.
+      auto it = node_boot_parts_index_ranges.find(parts.second.node);
+      if (it == node_boot_parts_index_ranges.end()) {
+        it =
+            node_boot_parts_index_ranges
+                .insert(std::make_pair(
+                    parts.second.node,
+                    std::vector<std::pair<std::string, std::pair<int, int>>>()))
+                .first;
+      }
+      std::vector<std::pair<std::string, std::pair<int, int>>>
+          &boot_parts_index_ranges = it->second;
+
+      // Find any existing ranges to extend, or make a new one otherwise.
+      auto parts_index_ranges_it = std::find_if(
+          boot_parts_index_ranges.begin(), boot_parts_index_ranges.end(),
+          [&](const std::pair<std::string, std::pair<int, int>> &val) {
+            return val.first == parts.second.source_boot_uuid;
+          });
+      if (parts_index_ranges_it == boot_parts_index_ranges.end()) {
+        boot_parts_index_ranges.emplace_back(
+            std::make_pair(parts.second.source_boot_uuid,
+                           std::make_pair(std::numeric_limits<int>::max(),
+                                          std::numeric_limits<int>::min())));
+        parts_index_ranges_it = boot_parts_index_ranges.end() - 1;
+      }
+
+      std::pair<int, int> &ranges = parts_index_ranges_it->second;
+
+      for (const std::pair<std::string, int> &part : parts.second.parts) {
+        ranges.first = std::min(ranges.first, part.second);
+        ranges.second = std::max(ranges.second, part.second);
+      }
+    }
+
+    // Now that we have ranges per node per boot, iterate through those and
+    // populate boot_constraints.
+    for (auto &boot_parts_index_ranges : node_boot_parts_index_ranges) {
+      auto it = boot_constraints.find(boot_parts_index_ranges.first);
+      if (it == boot_constraints.end()) {
+        it = boot_constraints
+                 .insert(std::make_pair(boot_parts_index_ranges.first,
+                                        NodeBootState()))
+                 .first;
+      }
+
+      // Sort the list by parts_index, look for overlaps, then insert
+      // everything as constraints.
+      std::sort(boot_parts_index_ranges.second.begin(),
+                boot_parts_index_ranges.second.end(), [](auto a, auto b) {
+                  return a.second.first < b.second.second;
+                });
+
+      std::map<std::string, std::vector<std::pair<std::string, bool>>>
+          &per_node_boot_constraints = it->second.constraints;
+
+      if (boot_parts_index_ranges.second.size() < 2) {
+        VLOG(1) << "Found only one boot for this node in this log.";
+        continue;
+      }
+
+      for (size_t i = 1; i < boot_parts_index_ranges.second.size(); ++i) {
+        CHECK_LT(boot_parts_index_ranges.second[i - 1].second.second,
+                 boot_parts_index_ranges.second[i].second.first)
+            << ": Overlapping parts_index, please investigate";
+        auto first_per_boot_constraints = per_node_boot_constraints.find(
+            boot_parts_index_ranges.second[i - 1].first);
+        if (first_per_boot_constraints == per_node_boot_constraints.end()) {
+          first_per_boot_constraints =
+              per_node_boot_constraints
+                  .insert(std::make_pair(
+                      boot_parts_index_ranges.second[i - 1].first,
+                      std::vector<std::pair<std::string, bool>>()))
+                  .first;
+        }
+
+        auto second_per_boot_constraints = per_node_boot_constraints.find(
+            boot_parts_index_ranges.second[i].first);
+        if (second_per_boot_constraints == per_node_boot_constraints.end()) {
+          second_per_boot_constraints =
+              per_node_boot_constraints
+                  .insert(std::make_pair(
+                      boot_parts_index_ranges.second[i].first,
+                      std::vector<std::pair<std::string, bool>>()))
+                  .first;
+        }
+
+        first_per_boot_constraints->second.emplace_back(
+            std::make_pair(boot_parts_index_ranges.second[i].first, true));
+        second_per_boot_constraints->second.emplace_back(
+            std::make_pair(boot_parts_index_ranges.second[i - 1].first, false));
+      }
+    }
+  }
+
+  // Print out our discovered constraints on request.
+  if (VLOG_IS_ON(2)) {
+    for (const std::pair<const std::string, NodeBootState> &node_state :
+         boot_constraints) {
+      LOG(INFO) << "Node " << node_state.first;
+      CHECK_GT(node_state.second.boots.size(), 0u)
+          << ": Need a boot from each node.";
+
+      for (const std::string &boot : node_state.second.boots) {
+        LOG(INFO) << "  boot " << boot;
+      }
+      for (const std::pair<std::string,
+                           std::vector<std::pair<std::string, bool>>>
+               &constraints : node_state.second.constraints) {
+        for (const std::pair<std::string, bool> &constraint :
+             constraints.second) {
+          if (constraint.second) {
+            LOG(INFO) << constraints.first << " < " << constraint.first;
+          } else {
+            LOG(INFO) << constraints.first << " > " << constraint.first;
+          }
+        }
+      }
+    }
+  }
+
+  // And now walk the constraint graph we have generated to order the boots.
+  // This doesn't need to catch all the cases, it just needs to report when it
+  // fails.
+  std::map<std::string, int> boot_count_map;
+
+  for (std::pair<const std::string, NodeBootState> &node_state :
+       boot_constraints) {
+    CHECK_GT(node_state.second.boots.size(), 0u)
+        << ": Need a boot from each node.";
+    if (node_state.second.boots.size() == 1u) {
+      boot_count_map.insert(
+          std::make_pair(*node_state.second.boots.begin(), 0));
+      continue;
+    }
+
+    // Now, walk the dag to find the earliest boot.  Pick a node and start
+    // traversing.
+    std::string current_boot = *node_state.second.boots.begin();
+    size_t update_count = 0;
+
+    while (true) {
+      auto it = node_state.second.constraints.find(current_boot);
+      if (it == node_state.second.constraints.end()) {
+        LOG(WARNING) << "Unconnected boot in set > 1";
+        break;
+      }
+
+      bool updated = false;
+      for (const std::pair<std::string, bool> &constraint : it->second) {
+        if (!constraint.second) {
+          updated = true;
+          current_boot = constraint.first;
+          break;
+        }
+      }
+      if (!updated) {
+        break;
+      }
+
+      ++update_count;
+
+      CHECK_LE(update_count, node_state.second.boots.size())
+          << ": Found a cyclic boot graph, giving up.";
+    }
+
+    // Now, walk the tree the other way to actually sort the boots.
+    // TODO(austin): We can probably drop sorted_boots and directly insert into
+    // the map with some more careful book-keeping.
+    std::vector<std::string> sorted_boots;
+    sorted_boots.emplace_back(current_boot);
+
+    update_count = 0;
+    while (true) {
+      auto it = node_state.second.constraints.find(current_boot);
+      if (it == node_state.second.constraints.end()) {
+        LOG(WARNING) << "Unconnected boot in set > 1";
+        break;
+      }
+
+      // This is a bit simplistic.  If you have a dag which isn't just a list,
+      // we aren't guarenteed to walk the tree correctly.
+      //
+      //  a < b
+      //  a < c
+      //  b < c
+      //
+      // That is rare enough in practice that we can CHECK and fix it if someone
+      // produces a valid use case.
+      bool updated = false;
+      for (const std::pair<std::string, bool> &constraint : it->second) {
+        if (constraint.second) {
+          updated = true;
+          current_boot = constraint.first;
+          break;
+        }
+      }
+      if (!updated) {
+        break;
+      }
+
+      sorted_boots.emplace_back(current_boot);
+
+      ++update_count;
+
+      CHECK_LE(update_count, node_state.second.boots.size())
+          << ": Found a cyclic boot graph, giving up.";
+    }
+
+    CHECK_EQ(sorted_boots.size(), node_state.second.boots.size())
+        << ": Graph failed to reach all the nodes.";
+
+    VLOG(1) << "Node " << node_state.first;
+    size_t boot_count = 0;
+    for (const std::string &boot : sorted_boots) {
+      VLOG(1) << "  Boot " << boot;
+      boot_count_map.insert(std::make_pair(std::move(boot), boot_count));
+      ++boot_count;
+    }
+  }
+
+  return boot_count_map;
+}
+
+std::vector<LogFile> PartsSorter::FormatNewParts() {
+  const std::map<std::string, int> boot_counts = ComputeBootCounts();
+
+  std::map<std::string, std::shared_ptr<const Configuration>>
+      copied_config_sha256;
   // Now, sort them and produce the final vector form.
   std::vector<LogFile> result;
   result.reserve(parts_list.size());
@@ -437,6 +740,11 @@
     new_file.log_event_uuid = logs.first;
     new_file.logger_node = logs.second.logger_node;
     new_file.logger_boot_uuid = logs.second.logger_boot_uuid;
+    {
+      auto boot_count_it = boot_counts.find(new_file.logger_boot_uuid);
+      CHECK(boot_count_it != boot_counts.end());
+      new_file.logger_boot_count = boot_count_it->second;
+    }
     new_file.monotonic_start_time = logs.second.monotonic_start_time;
     new_file.realtime_start_time = logs.second.realtime_start_time;
     new_file.name = logs.second.name;
@@ -457,6 +765,12 @@
       new_parts.parts_uuid = parts.first;
       new_parts.node = std::move(parts.second.node);
 
+      {
+        auto boot_count_it = boot_counts.find(new_parts.source_boot_uuid);
+        CHECK(boot_count_it != boot_counts.end());
+        new_parts.boot_count = boot_count_it->second;
+      }
+
       std::sort(parts.second.parts.begin(), parts.second.parts.end(),
                 [](const std::pair<std::string, int> &a,
                    const std::pair<std::string, int> &b) {
@@ -530,6 +844,29 @@
   return result;
 }
 
+std::vector<LogFile> SortParts(const std::vector<std::string> &parts) {
+  PartsSorter sorter;
+  sorter.PopulateFromFiles(parts);
+
+  if (sorter.old_parts.empty() && sorter.parts_list.empty()) {
+    if (parts.empty()) {
+      return std::vector<LogFile>{};
+    } else {
+      LogFile log_file;
+      log_file.corrupted = std::move(sorter.corrupted);
+      return std::vector<LogFile>{log_file};
+    }
+  }
+  CHECK_NE(sorter.old_parts.empty(), sorter.parts_list.empty())
+      << ": Can't have a mix of old and new parts.";
+
+  if (!sorter.old_parts.empty()) {
+    return sorter.FormatOldParts();
+  }
+
+  return sorter.FormatNewParts();
+}
+
 std::vector<std::string> FindNodes(const std::vector<LogFile> &parts) {
   std::set<std::string> nodes;
   for (const LogFile &log_file : parts) {
@@ -580,13 +917,13 @@
   if (!file.logger_boot_uuid.empty()) {
     stream << " \"logger_boot_uuid\": \"" << file.logger_boot_uuid << "\",\n";
   }
-  stream << " \"config\": " << file.config.get();
+  stream << " \"config\": \"" << file.config.get() << "\"";
   if (!file.config_sha256.empty()) {
     stream << ",\n \"config_sha256\": \"" << file.config_sha256 << "\"";
   }
-  stream << ",\n \"monotonic_start_time\": " << file.monotonic_start_time
-         << ",\n \"realtime_start_time\": " << file.realtime_start_time
-         << ",\n";
+  stream << ",\n \"monotonic_start_time\": \"" << file.monotonic_start_time
+         << "\",\n \"realtime_start_time\": \"" << file.realtime_start_time
+         << "\",\n";
   stream << " \"parts\": [\n";
   for (size_t i = 0; i < file.parts.size(); ++i) {
     if (i != 0u) {
@@ -610,20 +947,29 @@
   }
   if (!parts.source_boot_uuid.empty()) {
     stream << "  \"source_boot_uuid\": \"" << parts.source_boot_uuid << "\",\n";
+    stream << "  \"boot_count\": " << parts.boot_count << ",\n";
   }
-  stream << "  \"config\": " << parts.config.get();
+  stream << "  \"config\": \"" << parts.config.get() << "\"";
   if (!parts.config_sha256.empty()) {
     stream << ",\n  \"config_sha256\": \"" << parts.config_sha256 << "\"";
   }
-  stream << ",\n  \"monotonic_start_time\": " << parts.monotonic_start_time
-         << ",\n  \"realtime_start_time\": " << parts.realtime_start_time
-         << ",\n  \"parts\": [";
+  if (parts.logger_monotonic_start_time != aos::monotonic_clock::min_time) {
+    stream << ",\n  \"logger_monotonic_start_time\": \""
+           << parts.logger_monotonic_start_time << "\"";
+  }
+  if (parts.logger_realtime_start_time != aos::realtime_clock::min_time) {
+    stream << ",\n  \"logger_realtime_start_time\": \""
+           << parts.logger_realtime_start_time << "\"";
+  }
+  stream << ",\n  \"monotonic_start_time\": \"" << parts.monotonic_start_time
+         << "\",\n  \"realtime_start_time\": \"" << parts.realtime_start_time
+         << "\",\n  \"parts\": [";
 
   for (size_t i = 0; i < parts.parts.size(); ++i) {
     if (i != 0u) {
       stream << ", ";
     }
-    stream << parts.parts[i];
+    stream << "\"" << parts.parts[i] << "\"";
   }
 
   stream << "]\n }";
diff --git a/aos/events/logging/logfile_sorting.h b/aos/events/logging/logfile_sorting.h
index 964e592..1dd0cb3 100644
--- a/aos/events/logging/logfile_sorting.h
+++ b/aos/events/logging/logfile_sorting.h
@@ -38,6 +38,10 @@
   // data, this is the boot_uuid of the remote node.
   std::string source_boot_uuid;
 
+  // Boot number for this node.  This communicates the order of all the
+  // source_boot_uuid's for a node.
+  size_t boot_count = 0;
+
   // Pre-sorted list of parts.
   std::vector<std::string> parts;
 
@@ -50,7 +54,9 @@
 // Datastructure to hold parts from the same run of the logger which have no
 // ordering constraints relative to each other.
 struct LogFile {
-  // The UUID tying them all together (if available)
+  // The UUID tying them all together (if available).  This is set to a random
+  // uuid everytime a set of log files is started, regardless of if the logger
+  // starts and stops.
   std::string log_event_uuid;
 
   // The node the logger was running on (if available)
@@ -58,6 +64,9 @@
   // Boot UUID of the node running the logger.
   std::string logger_boot_uuid;
 
+  // Boot number for the logger node.
+  size_t logger_boot_count = 0;
+
   // The start time on the logger node.
   aos::monotonic_clock::time_point monotonic_start_time;
   aos::realtime_clock::time_point realtime_start_time;
diff --git a/aos/events/logging/logfile_utils.cc b/aos/events/logging/logfile_utils.cc
index b8b66a2..f4d4501 100644
--- a/aos/events/logging/logfile_utils.cc
+++ b/aos/events/logging/logfile_utils.cc
@@ -527,6 +527,8 @@
 }
 
 bool Message::operator<(const Message &m2) const {
+  CHECK_EQ(this->boot_count, m2.boot_count);
+
   if (this->timestamp < m2.timestamp) {
     return true;
   } else if (this->timestamp > m2.timestamp) {
@@ -544,13 +546,16 @@
 
 bool Message::operator>=(const Message &m2) const { return !(*this < m2); }
 bool Message::operator==(const Message &m2) const {
+  CHECK_EQ(this->boot_count, m2.boot_count);
+
   return timestamp == m2.timestamp && channel_index == m2.channel_index &&
          queue_index == m2.queue_index;
 }
 
 std::ostream &operator<<(std::ostream &os, const Message &m) {
   os << "{.channel_index=" << m.channel_index
-     << ", .queue_index=" << m.queue_index << ", .timestamp=" << m.timestamp;
+     << ", .queue_index=" << m.queue_index << ", .timestamp=" << m.timestamp
+     << ", .boot_count=" << m.boot_count;
   if (m.data.Verify()) {
     os << ", .data="
        << aos::FlatbufferToJson(m.data,
@@ -608,12 +613,13 @@
         break;
       }
 
-      messages_.insert(
-          {.channel_index = m.value().message().channel_index(),
-           .queue_index = m.value().message().queue_index(),
-           .timestamp = monotonic_clock::time_point(std::chrono::nanoseconds(
-               m.value().message().monotonic_sent_time())),
-           .data = std::move(m.value())});
+      messages_.insert(Message{
+          .channel_index = m.value().message().channel_index(),
+          .queue_index = m.value().message().queue_index(),
+          .timestamp = monotonic_clock::time_point(std::chrono::nanoseconds(
+              m.value().message().monotonic_sent_time())),
+          .boot_count = parts().boot_count,
+          .data = std::move(m.value())});
 
       // Now, update sorted_until_ to match the new message.
       if (parts_message_reader_.newest_timestamp() >
@@ -662,16 +668,22 @@
 
 NodeMerger::NodeMerger(std::vector<LogParts> parts) {
   CHECK_GE(parts.size(), 1u);
-  const std::string part0_node = parts[0].node;
+  // Enforce that we are sorting things only from a single node from a single
+  // boot.
+  const std::string_view part0_node = parts[0].node;
+  const std::string_view part0_source_boot_uuid = parts[0].source_boot_uuid;
   for (size_t i = 1; i < parts.size(); ++i) {
     CHECK_EQ(part0_node, parts[i].node) << ": Can't merge different nodes.";
+    CHECK_EQ(part0_source_boot_uuid, parts[i].source_boot_uuid)
+        << ": Can't merge different boots.";
   }
+
+  node_ = configuration::GetNodeIndex(parts[0].config.get(), part0_node);
+
   for (LogParts &part : parts) {
     parts_sorters_.emplace_back(std::move(part));
   }
 
-  node_ = configuration::GetNodeIndex(configuration(), part0_node);
-
   monotonic_start_time_ = monotonic_clock::max_time;
   realtime_start_time_ = realtime_clock::max_time;
   for (const LogPartsSorter &parts_sorter : parts_sorters_) {
@@ -750,6 +762,49 @@
   current_ = nullptr;
 }
 
+BootMerger::BootMerger(std::vector<LogParts> files) {
+  std::vector<std::vector<LogParts>> boots;
+
+  // Now, we need to split things out by boot.
+  for (size_t i = 0; i < files.size(); ++i) {
+    LOG(INFO) << "Trying file " << i;
+    const size_t boot_count = files[i].boot_count;
+    LOG(INFO) << "Boot count " << boot_count;
+    if (boot_count + 1 > boots.size()) {
+      boots.resize(boot_count + 1);
+    }
+    boots[boot_count].emplace_back(std::move(files[i]));
+  }
+
+  node_mergers_.reserve(boots.size());
+  for (size_t i = 0; i < boots.size(); ++i) {
+    LOG(INFO) << "Boot " << i;
+    for (auto &p : boots[i]) {
+      LOG(INFO) << "Part " << p;
+    }
+    node_mergers_.emplace_back(
+        std::make_unique<NodeMerger>(std::move(boots[i])));
+  }
+}
+
+Message *BootMerger::Front() {
+  Message *result = node_mergers_[index_]->Front();
+
+  if (result != nullptr) {
+    return result;
+  }
+
+  if (index_ + 1u == node_mergers_.size()) {
+    // At the end of the last node merger, just return.
+    return nullptr;
+  } else {
+    ++index_;
+    return Front();
+  }
+}
+
+void BootMerger::PopFront() { node_mergers_[index_]->PopFront(); }
+
 TimestampMapper::TimestampMapper(std::vector<LogParts> parts)
     : node_merger_(std::move(parts)),
       timestamp_callback_([](TimestampedMessage *) {}) {
@@ -983,6 +1038,7 @@
         .channel_index = message.channel_index,
         .queue_index = remote_queue_index,
         .timestamp = monotonic_remote_time,
+        .boot_count = 0,
         .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
   }
 
@@ -997,6 +1053,7 @@
         .channel_index = message.channel_index,
         .queue_index = remote_queue_index,
         .timestamp = monotonic_remote_time,
+        .boot_count = 0,
         .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
   }
 
@@ -1006,6 +1063,7 @@
         .channel_index = message.channel_index,
         .queue_index = remote_queue_index,
         .timestamp = monotonic_remote_time,
+        .boot_count = 0,
         .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
   }
 
@@ -1040,6 +1098,7 @@
           .channel_index = message.channel_index,
           .queue_index = remote_queue_index,
           .timestamp = monotonic_remote_time,
+          .boot_count = 0,
           .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
     }
 
diff --git a/aos/events/logging/logfile_utils.h b/aos/events/logging/logfile_utils.h
index 2219a07..2632302 100644
--- a/aos/events/logging/logfile_utils.h
+++ b/aos/events/logging/logfile_utils.h
@@ -350,6 +350,9 @@
   uint32_t queue_index = 0xffffffff;
   // The local timestamp on the monotonic clock.
   monotonic_clock::time_point timestamp = monotonic_clock::min_time;
+  // The current boot count added on by SortParts.
+  size_t boot_count = 0;
+
   // The data (either a timestamp header, or a data header).
   SizePrefixedFlatbufferVector<MessageHeader> data;
 
@@ -431,6 +434,13 @@
  public:
   NodeMerger(std::vector<LogParts> parts);
 
+  // Copying and moving will mess up the internal raw pointers.  Just don't do
+  // it.
+  NodeMerger(NodeMerger const &) = delete;
+  NodeMerger(NodeMerger &&) = delete;
+  void operator=(NodeMerger const &) = delete;
+  void operator=(NodeMerger &&) = delete;
+
   // Node index in the configuration of this node.
   int node() const { return node_; }
 
@@ -478,6 +488,56 @@
   monotonic_clock::time_point monotonic_start_time_ = monotonic_clock::max_time;
 };
 
+// Class to concatenate multiple boots worth of logs into a single per-node
+// stream.
+class BootMerger {
+ public:
+  BootMerger(std::vector<LogParts> file);
+
+  // Copying and moving will mess up the internal raw pointers.  Just don't do
+  // it.
+  BootMerger(BootMerger const &) = delete;
+  BootMerger(BootMerger &&) = delete;
+  void operator=(BootMerger const &) = delete;
+  void operator=(BootMerger &&) = delete;
+
+  // Node index in the configuration of this node.
+  int node() const { return node_mergers_[0]->node(); }
+
+  // List of parts being sorted together.
+  std::vector<const LogParts *> Parts() const;
+
+  const Configuration *configuration() const {
+    return node_mergers_[0]->configuration();
+  }
+
+  monotonic_clock::time_point monotonic_start_time() const {
+    return node_mergers_[index_]->monotonic_start_time();
+  }
+  realtime_clock::time_point realtime_start_time() const {
+    return node_mergers_[index_]->realtime_start_time();
+  }
+
+  bool started() const {
+    return node_mergers_[index_]->sorted_until() != monotonic_clock::min_time ||
+           index_ != 0;
+  }
+
+  // Returns the next sorted message from the set of log files.  It is safe to
+  // call std::move() on the result to move the data flatbuffer from it.
+  Message *Front();
+  // Pops the front message.  This should only be called after a call to
+  // Front().
+  void PopFront();
+
+ private:
+  int index_ = 0;
+
+  // TODO(austin): Sanjay points out this is pretty inefficient.  Don't keep so
+  // many things open.
+  std::vector<std::unique_ptr<NodeMerger>> node_mergers_;
+};
+
 // Class to match timestamps with the corresponding data from other nodes.
 //
 // This class also buffers data for the node it represents, and supports
@@ -498,8 +558,6 @@
   // timestamps out of this queue.  This lets us bootstrap time estimation
   // without exploding memory usage worst case.
 
-  std::vector<const LogParts *> Parts() const { return node_merger_.Parts(); }
-
   const Configuration *configuration() const { return configuration_.get(); }
 
   // Returns which node this is sorting for.
@@ -518,9 +576,9 @@
   // node.
   void AddPeer(TimestampMapper *timestamp_mapper);
 
-  // Time that we are sorted until internally.
-  monotonic_clock::time_point sorted_until() const {
-    return node_merger_.sorted_until();
+  // Returns true if anything has been queued up.
+  bool started() const {
+    return node_merger_.sorted_until() != monotonic_clock::min_time;
   }
 
   // Returns the next message for this node.
diff --git a/aos/events/logging/logfile_utils_test.cc b/aos/events/logging/logfile_utils_test.cc
index 384772c..d5cb41b 100644
--- a/aos/events/logging/logfile_utils_test.cc
+++ b/aos/events/logging/logfile_utils_test.cc
@@ -224,10 +224,12 @@
   Message m1{.channel_index = 0,
              .queue_index = 0,
              .timestamp = e + chrono::milliseconds(1),
+             .boot_count = 0,
              .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
   Message m2{.channel_index = 0,
              .queue_index = 0,
              .timestamp = e + chrono::milliseconds(2),
+             .boot_count = 0,
              .data = SizePrefixedFlatbufferVector<MessageHeader>::Empty()};
 
   EXPECT_LT(m1, m2);
@@ -839,7 +841,7 @@
     EXPECT_EQ(mapper1_count, 0u);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), e + chrono::milliseconds(1900));
+    EXPECT_TRUE(mapper0.started());
     EXPECT_EQ(mapper0_count, 1u);
     EXPECT_EQ(mapper1_count, 0u);
 
@@ -848,12 +850,12 @@
     EXPECT_EQ(mapper1_count, 0u);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), e + chrono::milliseconds(2900));
+    EXPECT_TRUE(mapper0.started());
 
     ASSERT_TRUE(mapper0.Front() != nullptr);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper0.started());
 
     EXPECT_EQ(mapper0_count, 3u);
     EXPECT_EQ(mapper1_count, 0u);
@@ -880,8 +882,7 @@
     EXPECT_EQ(mapper1_count, 1u);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(1900));
+    EXPECT_TRUE(mapper1.started());
     EXPECT_EQ(mapper0_count, 3u);
     EXPECT_EQ(mapper1_count, 1u);
 
@@ -890,13 +891,12 @@
     EXPECT_EQ(mapper1_count, 2u);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(2900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper1.started());
 
     EXPECT_EQ(mapper0_count, 3u);
     EXPECT_EQ(mapper1_count, 3u);
@@ -1071,19 +1071,17 @@
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(1900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(2900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() == nullptr);
 
@@ -1104,17 +1102,17 @@
     ASSERT_TRUE(mapper0.Front() != nullptr);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper0.started());
 
     ASSERT_TRUE(mapper0.Front() != nullptr);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper0.started());
 
     ASSERT_TRUE(mapper0.Front() != nullptr);
     output0.emplace_back(std::move(*mapper0.Front()));
     mapper0.PopFront();
-    EXPECT_EQ(mapper0.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper0.started());
 
     ASSERT_TRUE(mapper0.Front() == nullptr);
 
@@ -1179,19 +1177,17 @@
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(1900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(2900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() == nullptr);
 
@@ -1259,19 +1255,17 @@
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(1900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(),
-              e + chrono::seconds(100) + chrono::milliseconds(2900));
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() != nullptr);
     output1.emplace_back(std::move(*mapper1.Front()));
     mapper1.PopFront();
-    EXPECT_EQ(mapper1.sorted_until(), monotonic_clock::max_time);
+    EXPECT_TRUE(mapper1.started());
 
     ASSERT_TRUE(mapper1.Front() == nullptr);
 
@@ -1675,6 +1669,131 @@
   }
 }
 
+class BootMergerTest : public SortingElementTest {
+ public:
+  BootMergerTest()
+      : SortingElementTest(),
+        boot0_(MakeHeader(config_, R"({
+  /* 100ms */
+  "max_out_of_order_duration": 100000000,
+  "node": {
+    "name": "pi2"
+  },
+  "logger_node": {
+    "name": "pi1"
+  },
+  "monotonic_start_time": 1000000,
+  "realtime_start_time": 1000000000000,
+  "logger_monotonic_start_time": 1000000,
+  "logger_realtime_start_time": 1000000000000,
+  "log_event_uuid": "30ef1283-81d7-4004-8c36-1c162dbcb2b2",
+  "parts_uuid": "1a9e5ca2-31b2-475b-8282-88f6d1ce5109",
+  "parts_index": 0,
+  "logger_instance_uuid": "1c3142ad-10a5-408d-a760-b63b73d3b904",
+  "logger_node_boot_uuid": "a570df8b-5cc2-4dbe-89bd-286f9ddd02b7",
+  "source_node_boot_uuid": "6ba4f28d-21a2-4d7f-83f4-ee365cf86464"
+})")),
+        boot1_(MakeHeader(config_, R"({
+  /* 100ms */
+  "max_out_of_order_duration": 100000000,
+  "node": {
+    "name": "pi2"
+  },
+  "logger_node": {
+    "name": "pi1"
+  },
+  "monotonic_start_time": 1000000,
+  "realtime_start_time": 1000000000000,
+  "logger_monotonic_start_time": 1000000,
+  "logger_realtime_start_time": 1000000000000,
+  "log_event_uuid": "30ef1283-81d7-4004-8c36-1c162dbcb2b2",
+  "parts_uuid": "2a05d725-5d5c-4c0b-af42-88de2f3c3876",
+  "parts_index": 1,
+  "logger_instance_uuid": "1c3142ad-10a5-408d-a760-b63b73d3b904",
+  "logger_node_boot_uuid": "a570df8b-5cc2-4dbe-89bd-286f9ddd02b7",
+  "source_node_boot_uuid": "b728d27a-9181-4eac-bfc1-5d09b80469d2"
+})")) {}
+
+ protected:
+  const aos::SizePrefixedFlatbufferDetachedBuffer<LogFileHeader> boot0_;
+  const aos::SizePrefixedFlatbufferDetachedBuffer<LogFileHeader> boot1_;
+};
+
+// This tests that we can properly sort a multi-node log file which has the old
+// (and buggy) timestamps in the header, and the non-resetting parts_index.
+// These make it so we can just bairly figure out what happened first and what
+// happened second, but not in a way that is robust to multiple nodes rebooting.
+TEST_F(BootMergerTest, OldReboot) {
+  {
+    DetachedBufferWriter writer(logfile0_, std::make_unique<DummyEncoder>());
+    writer.QueueSpan(boot0_.span());
+  }
+  {
+    DetachedBufferWriter writer(logfile1_, std::make_unique<DummyEncoder>());
+    writer.QueueSpan(boot1_.span());
+  }
+
+  const std::vector<LogFile> parts = SortParts({logfile0_, logfile1_});
+
+  ASSERT_EQ(parts.size(), 1u);
+  ASSERT_EQ(parts[0].parts.size(), 2u);
+
+  EXPECT_EQ(parts[0].parts[0].boot_count, 0);
+  EXPECT_EQ(parts[0].parts[0].source_boot_uuid,
+            boot0_.message().source_node_boot_uuid()->string_view());
+
+  EXPECT_EQ(parts[0].parts[1].boot_count, 1);
+  EXPECT_EQ(parts[0].parts[1].source_boot_uuid,
+            boot1_.message().source_node_boot_uuid()->string_view());
+}
+
+// This tests that we can produce messages ordered across a reboot.
+TEST_F(BootMergerTest, SortAcrossReboot) {
+  const aos::monotonic_clock::time_point e = monotonic_clock::epoch();
+  {
+    DetachedBufferWriter writer(logfile0_, std::make_unique<DummyEncoder>());
+    writer.QueueSpan(boot0_.span());
+    writer.QueueSizedFlatbuffer(
+        MakeLogMessage(e + chrono::milliseconds(1000), 0, 0x005));
+    writer.QueueSizedFlatbuffer(
+        MakeLogMessage(e + chrono::milliseconds(2000), 1, 0x105));
+  }
+  {
+    DetachedBufferWriter writer(logfile1_, std::make_unique<DummyEncoder>());
+    writer.QueueSpan(boot1_.span());
+    writer.QueueSizedFlatbuffer(
+        MakeLogMessage(e + chrono::milliseconds(100), 0, 0x006));
+    writer.QueueSizedFlatbuffer(
+        MakeLogMessage(e + chrono::milliseconds(200), 1, 0x106));
+  }
+
+  const std::vector<LogFile> parts = SortParts({logfile0_, logfile1_});
+  ASSERT_EQ(parts.size(), 1u);
+  ASSERT_EQ(parts[0].parts.size(), 2u);
+
+  BootMerger merger(FilterPartsForNode(parts, "pi2"));
+
+  EXPECT_EQ(merger.node(), 1u);
+
+  std::vector<Message> output;
+  for (int i = 0; i < 4; ++i) {
+    ASSERT_TRUE(merger.Front() != nullptr);
+    output.emplace_back(std::move(*merger.Front()));
+    merger.PopFront();
+  }
+
+  ASSERT_TRUE(merger.Front() == nullptr);
+
+  EXPECT_EQ(output[0].timestamp, e + chrono::milliseconds(1000));
+  EXPECT_EQ(output[0].boot_count, 0u);
+  EXPECT_EQ(output[1].timestamp, e + chrono::milliseconds(2000));
+  EXPECT_EQ(output[1].boot_count, 0u);
+  EXPECT_EQ(output[2].timestamp, e + chrono::milliseconds(100));
+  EXPECT_EQ(output[2].boot_count, 1u);
+  EXPECT_EQ(output[3].timestamp, e + chrono::milliseconds(200));
+  EXPECT_EQ(output[3].boot_count, 1u);
+}
+
 }  // namespace testing
 }  // namespace logger
 }  // namespace aos
diff --git a/aos/network/BUILD b/aos/network/BUILD
index e6ff5af..067ae35 100644
--- a/aos/network/BUILD
+++ b/aos/network/BUILD
@@ -105,8 +105,8 @@
     ],
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
-        "//aos/util:string_to_num",
         "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/strings",
     ],
 )
 
diff --git a/aos/network/multinode_timestamp_filter.cc b/aos/network/multinode_timestamp_filter.cc
index d7bbff0..cafb940 100644
--- a/aos/network/multinode_timestamp_filter.cc
+++ b/aos/network/multinode_timestamp_filter.cc
@@ -674,7 +674,7 @@
   size_t node_index = 0;
   for (logger::TimestampMapper *timestamp_mapper : timestamp_mappers) {
     if (timestamp_mapper != nullptr) {
-      CHECK_EQ(timestamp_mapper->sorted_until(), monotonic_clock::min_time)
+      CHECK(!timestamp_mapper->started())
           << ": Timestamps queued before we registered the timestamp hooks.";
       timestamp_mapper->set_timestamp_callback(
           [this, node_index](logger::TimestampedMessage *msg) {
diff --git a/aos/network/team_number.cc b/aos/network/team_number.cc
index 1f71946..0bd0cf7 100644
--- a/aos/network/team_number.cc
+++ b/aos/network/team_number.cc
@@ -5,7 +5,7 @@
 #include <stdlib.h>
 #include <unistd.h>
 
-#include "aos/util/string_to_num.h"
+#include "absl/strings/numbers.h"
 
 DEFINE_string(
     override_hostname, "",
@@ -16,16 +16,17 @@
 namespace network {
 namespace team_number_internal {
 
-std::optional<uint16_t> ParseRoborioTeamNumber(const std::string &hostname) {
+std::optional<uint16_t> ParseRoborioTeamNumber(
+    const std::string_view hostname) {
   for (size_t i = 0; i < hostname.size(); i++) {
     if (hostname[i] == '-') {
-      const std::string num_as_s =
+      const std::string_view num_as_s =
           hostname[hostname.size() - 1] == 'C'
               ? hostname.substr(i + 1, hostname.size() - 5 - i)
               : hostname.substr(i + 1);
 
       int num;
-      if (!::aos::util::StringToNumber(num_as_s, &num)) {
+      if (!absl::SimpleAtoi(num_as_s, &num)) {
         return std::nullopt;
       }
       if (hostname.substr(0, i) == "roboRIO" &&
@@ -38,7 +39,7 @@
   return std::nullopt;
 }
 
-std::optional<uint16_t> ParsePiTeamNumber(const std::string &hostname) {
+std::optional<uint16_t> ParsePiTeamNumber(const std::string_view hostname) {
   if (hostname.substr(0, 3) != "pi-") {
     return std::nullopt;
   }
@@ -52,10 +53,10 @@
   if (second_separator == hostname.npos) {
     return std::nullopt;
   }
-  const std::string number_string =
+  const std::string_view number_string =
       hostname.substr(first_separator, second_separator - first_separator);
   int number;
-  if (!util::StringToNumber(number_string, &number)) {
+  if (!absl::SimpleAtoi(number_string, &number)) {
     return std::nullopt;
   }
   return number;
@@ -74,8 +75,8 @@
 
   const char *override_number = getenv("AOS_TEAM_NUMBER");
   if (override_number != nullptr) {
-    uint16_t result;
-    if (!::aos::util::StringToNumber(override_number, &result)) {
+    uint32_t result;
+    if (!absl::SimpleAtoi(override_number, &result)) {
       LOG(FATAL) << "Error parsing AOS_TEAM_NUMBER: " << override_number;
     }
     LOG(WARNING)
@@ -121,7 +122,7 @@
 
 void OverrideTeamNumber(uint16_t team) { override_team = team; }
 
-std::optional<uint16_t> ParsePiNumber(const std::string &hostname) {
+std::optional<uint16_t> ParsePiNumber(const std::string_view hostname) {
   if (hostname.substr(0, 3) != "pi-") {
     return std::nullopt;
   }
@@ -135,14 +136,14 @@
   if (second_separator == hostname.npos) {
     return std::nullopt;
   }
-  const std::string number_string = hostname.substr(
+  const std::string_view number_string = hostname.substr(
       second_separator + 1, hostname.size() - second_separator - 1);
   if (number_string.size() == 0) {
     return std::nullopt;
   }
 
   int number;
-  if (!util::StringToNumber(number_string, &number)) {
+  if (!absl::SimpleAtoi(number_string, &number)) {
     return std::nullopt;
   }
   return number;
diff --git a/aos/network/team_number.h b/aos/network/team_number.h
index c2954b6..8effc27 100644
--- a/aos/network/team_number.h
+++ b/aos/network/team_number.h
@@ -4,7 +4,7 @@
 #include <stdint.h>
 
 #include <optional>
-#include <string>
+#include <string_view>
 
 #include "glog/logging.h"
 
@@ -29,14 +29,14 @@
 void OverrideTeamNumber(uint16_t team);
 
 // Returns the pi number for a pi formated hostname.  pi-team#-pi# (pi-971-5)
-std::optional<uint16_t> ParsePiNumber(const std::string &hostname);
+std::optional<uint16_t> ParsePiNumber(const std::string_view hostname);
 
 namespace team_number_internal {
 
-std::optional<uint16_t> ParseRoborioTeamNumber(const std::string &hostname);
+std::optional<uint16_t> ParseRoborioTeamNumber(const std::string_view hostname);
 
 // Returns the team number for a pi formated hostname.  pi-team#-pi#
-std::optional<uint16_t> ParsePiTeamNumber(const std::string &hostname);
+std::optional<uint16_t> ParsePiTeamNumber(const std::string_view hostname);
 
 }  // namespace team_number_internal
 }  // namespace network
diff --git a/aos/util/BUILD b/aos/util/BUILD
index 7c5052c..59dec18 100644
--- a/aos/util/BUILD
+++ b/aos/util/BUILD
@@ -119,26 +119,6 @@
 )
 
 cc_library(
-    name = "string_to_num",
-    hdrs = [
-        "string_to_num.h",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-)
-
-cc_test(
-    name = "string_to_num_test",
-    srcs = [
-        "string_to_num_test.cc",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        ":string_to_num",
-        "//aos/testing:googletest",
-    ],
-)
-
-cc_library(
     name = "trapezoid_profile",
     srcs = [
         "trapezoid_profile.cc",
diff --git a/aos/util/string_to_num.h b/aos/util/string_to_num.h
deleted file mode 100644
index 86210ca..0000000
--- a/aos/util/string_to_num.h
+++ /dev/null
@@ -1,29 +0,0 @@
-#ifndef AOS_UTIL_STRING_TO_NUM_H_
-#define AOS_UTIL_STRING_TO_NUM_H_
-
-#include <sstream>
-#include <string>
-
-namespace aos {
-namespace util {
-
-// Converts a string into a specified numeric type. If it can't be converted
-// completely or at all, or if the converted number would overflow the
-// specified type, it returns false.
-template<typename T>
-inline bool StringToNumber(const ::std::string &input, T *out_num) {
-  ::std::istringstream stream(input);
-  stream >> *out_num;
-
-  if (stream.fail() || !stream.eof()) {
-    return false;
-  }
-
-  return true;
-}
-
-
-}  // util
-}  // aos
-
-#endif
diff --git a/aos/util/string_to_num_test.cc b/aos/util/string_to_num_test.cc
deleted file mode 100644
index 3f467cf..0000000
--- a/aos/util/string_to_num_test.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include <stdint.h>
-
-#include <string>
-
-#include "gtest/gtest.h"
-
-#include "aos/util/string_to_num.h"
-
-namespace aos {
-namespace util {
-namespace testing {
-
-TEST(StringToNumTest, CorrectNumber) {
-  int result;
-  ASSERT_TRUE(StringToNumber<int>(::std::string("42"), &result));
-  EXPECT_EQ(result, 42);
-}
-
-TEST(StringToNumTest, NegativeTest) {
-  int result;
-  ASSERT_TRUE(StringToNumber<int>(::std::string("-42"), &result));
-  EXPECT_EQ(result, -42);
-}
-
-TEST(StringToNumTest, NonNumber) {
-  int result;
-  ASSERT_FALSE(StringToNumber<int>(::std::string("Daniel"), &result));
-}
-
-TEST(StringToNumTest, NumberWithText) {
-  int result;
-  ASSERT_FALSE(StringToNumber<int>(::std::string("42Daniel"), &result));
-}
-
-TEST(StringToNumTest, OverflowTest) {
-  uint32_t result;
-  // 2 << 32 should overflow.
-  ASSERT_FALSE(StringToNumber<uint32_t>(::std::string("4294967296"), &result));
-}
-
-TEST(StringToNumTest, FloatingPointTest) {
-  double result;
-  ASSERT_TRUE(StringToNumber<double>(::std::string("3.1415927"), &result));
-  EXPECT_EQ(result, 3.1415927);
-}
-
-}  // testing
-}  // util
-}  // aos
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index f56c429..7cb0b4d 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -6,13 +6,6 @@
 load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library", "flatbuffer_ts_library")
 load("//aos:config.bzl", "aos_config")
 
-py_library(
-    name = "python_init",
-    srcs = ["__init__.py"],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = ["//frc971:python_init"],
-)
-
 cc_binary(
     name = "py_log_reader.so",
     srcs = ["py_log_reader.cc"],
@@ -40,36 +33,6 @@
     deps = ["//aos:configuration_fbs_python"],
 )
 
-py_proto_library(
-    name = "plot_config_proto",
-    srcs = ["plot_config.proto"],
-    target_compatible_with = ["@platforms//os:linux"],
-)
-
-py_binary(
-    name = "plot",
-    srcs = ["plot.py"],
-    data = [
-        ":py_log_reader.so",
-    ] + glob(["plot_configs/**"]),
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [
-        ":plot_config_proto",
-        ":python_init",
-        "@matplotlib_repo//:matplotlib3",
-    ],
-)
-
-py_test(
-    name = "plot_test",
-    srcs = ["plot_test.py"],
-    data = [
-        "@sample_logfile//file",
-    ],
-    target_compatible_with = ["@platforms//os:linux"],
-    deps = [":plot"],
-)
-
 ts_library(
     name = "plot_index",
     srcs = ["plot_index.ts"],
diff --git a/frc971/analysis/__init__.py b/frc971/analysis/__init__.py
deleted file mode 100644
index e69de29..0000000
--- a/frc971/analysis/__init__.py
+++ /dev/null
diff --git a/frc971/analysis/drivetrain_down_stripped b/frc971/analysis/drivetrain_down_stripped
deleted file mode 100644
index 3b3e43d..0000000
--- a/frc971/analysis/drivetrain_down_stripped
+++ /dev/null
@@ -1,4 +0,0 @@
-drivetrain.stripped output left_voltage
-drivetrain.stripped output right_voltage
-
-drivetrain.stripped status ground_angle
diff --git a/frc971/analysis/drivetrain_plot_stripped b/frc971/analysis/drivetrain_plot_stripped
deleted file mode 100644
index 3c24485..0000000
--- a/frc971/analysis/drivetrain_plot_stripped
+++ /dev/null
@@ -1,20 +0,0 @@
-drivetrain.stripped output left_voltage
-drivetrain.stripped output right_voltage
-
-drivetrain.stripped status profiled_left_position_goal
-drivetrain.stripped status profiled_right_position_goal
-drivetrain.stripped status profiled_left_velocity_goal
-drivetrain.stripped status profiled_right_velocity_goal
-
-drivetrain.stripped status estimated_left_position
-drivetrain.stripped status estimated_right_position
-drivetrain.stripped status estimated_left_velocity
-drivetrain.stripped status estimated_right_velocity
-
-drivetrain.stripped goal left_goal
-drivetrain.stripped goal right_goal
-
-drivetrain.stripped status left_voltage_error -m 0.1
-drivetrain.stripped status right_voltage_error -m 0.1
-
-drivetrain.stripped using accelerometer_y -m -10
diff --git a/frc971/analysis/drivetrain_test_plot b/frc971/analysis/drivetrain_test_plot
deleted file mode 100644
index 0b2cc2a..0000000
--- a/frc971/analysis/drivetrain_test_plot
+++ /dev/null
@@ -1,16 +0,0 @@
-drivetrain_lib_test output left_voltage
-drivetrain_lib_test output right_voltage
-
-drivetrain_lib_test status estimated_left_position
-drivetrain_lib_test status estimated_right_position
-drivetrain_lib_test status estimated_left_velocity
-drivetrain_lib_test status estimated_right_velocity
-
-drivetrain_lib_test goal left_goal
-drivetrain_lib_test goal right_goal
-drivetrain_lib_test status profiled_left_position_goal
-drivetrain_lib_test status profiled_right_position_goal
-drivetrain_lib_test status profiled_left_velocity_goal
-drivetrain_lib_test status profiled_right_velocity_goal
-
-robot_state browned_out
diff --git a/frc971/analysis/plot.py b/frc971/analysis/plot.py
deleted file mode 100644
index efe86f4..0000000
--- a/frc971/analysis/plot.py
+++ /dev/null
@@ -1,306 +0,0 @@
-#!/usr/bin/python3
-# Sample usage:
-# bazel run -c opt //frc971/analysis:plot  -- --logfile /tmp/log.fbs --config gyro.pb
-import argparse
-import json
-import os.path
-from pathlib import Path
-import sys
-
-from frc971.analysis.py_log_reader import LogReader
-from frc971.analysis.plot_config_pb2 import PlotConfig, Signal, Line
-from google.protobuf import text_format
-
-import numpy as np
-import matplotlib
-from matplotlib import pyplot as plt
-
-
-class Plotter:
-    def __init__(self, plot_config: PlotConfig, reader: LogReader):
-        self.config = plot_config
-        self.reader = reader
-        # Data streams, indexed by alias.
-        self.data = {}
-
-    def process_logfile(self):
-        aliases = set()
-        for channel in self.config.channel:
-            if channel.alias in aliases:
-                raise ValueError("Duplicate alias " + channel.alias)
-            if not self.reader.subscribe(channel.name, channel.type):
-                print("Warning: No such channel with name " + channel.name +
-                      " and type " + channel.type)
-                continue
-            aliases.add(channel.alias)
-
-        self.reader.process()
-
-        for channel in self.config.channel:
-            self.data[channel.alias] = []
-            if channel.alias not in aliases:
-                print("Unable to plot channel alias " + channel.alias)
-                continue
-            for message in self.reader.get_data_for_channel(
-                    channel.name, channel.type):
-                valid_json = message[2].replace('nan', '"nan"')
-                valid_json = valid_json.replace(' inf', ' "inf"')
-                valid_json = valid_json.replace('-inf', '"-inf"')
-                try:
-                    parsed_json = json.loads(valid_json)
-                except json.decoder.JSONDecodeError as ex:
-                    print("JSON Decode failed:")
-                    print(valid_json)
-                    raise ex
-                self.data[channel.alias].append(
-                    (message[0], message[1], parsed_json))
-        self.calculate_signals()
-
-    def calculate_down_estimator_signals(self):
-        if 'DrivetrainStatus' in self.data:
-            # Calculates a rolling mean of the acceleration output from
-            # the down estimator.
-            entries = []
-            buffer_len = 100
-            last_100_accels = np.zeros((buffer_len, 3))
-            accels_next_row = 0
-            for entry in self.data['DrivetrainStatus']:
-                msg = entry[2]
-                new_msg = {}
-                if 'down_estimator' not in msg:
-                    continue
-                down_estimator = msg['down_estimator']
-                new_msg['down_estimator'] = {}
-                accel_x = 'accel_x'
-                accel_y = 'accel_y'
-                accel_z = 'accel_z'
-                if (accel_x in down_estimator and accel_y in down_estimator
-                        and accel_x in down_estimator):
-                    last_100_accels[accels_next_row, :] = [
-                        down_estimator[accel_x], down_estimator[accel_y],
-                        down_estimator[accel_z]
-                    ]
-
-                    accels_next_row += 1
-                    accels_next_row = accels_next_row % buffer_len
-                    mean_accels = np.mean(last_100_accels, axis=0)
-                    new_msg['down_estimator'][
-                        'accel_x_rolling_mean'] = mean_accels[0]
-                    new_msg['down_estimator'][
-                        'accel_y_rolling_mean'] = mean_accels[1]
-                    new_msg['down_estimator'][
-                        'accel_z_rolling_mean'] = mean_accels[2]
-                entries.append((entry[0], entry[1], new_msg))
-            if 'CalcDrivetrainStatus' in self.data:
-                raise RuntimeError(
-                    'CalcDrivetrainStatus is already a member of data.')
-            self.data['CalcDrivetrainStatus'] = entries
-
-    def calculate_imu_signals(self):
-        if 'IMU' in self.data:
-            entries = []
-            # Calculates a rolling mean of the raw output from the IMU.
-            buffer_len = 1000
-            last_1000_accels = np.zeros((buffer_len, 3))
-            accels_next_row = 0
-            last_1000_gyros = np.zeros((buffer_len, 3))
-            gyros_next_row = 0
-            for entry in self.data['IMU']:
-                for msg in entry[2]['readings']:
-                    accel_x = 'accelerometer_x'
-                    accel_y = 'accelerometer_y'
-                    accel_z = 'accelerometer_z'
-                    gyro_x = 'gyro_x'
-                    gyro_y = 'gyro_y'
-                    gyro_z = 'gyro_z'
-                    temp = 'temperature'
-                    new_msg = {}
-                    if temp in msg:
-                        new_msg[temp] = msg[temp]
-                    if accel_x in msg and accel_y in msg and accel_x in msg:
-                        last_1000_accels[accels_next_row, :] = [
-                            msg[accel_x], msg[accel_y], msg[accel_z]
-                        ]
-                        total_acceleration = np.linalg.norm(
-                            last_1000_accels[accels_next_row, :])
-                        new_msg['total_acceleration'] = total_acceleration
-
-                        accels_next_row += 1
-                        accels_next_row = accels_next_row % buffer_len
-                        std_accels = np.std(last_1000_accels, axis=0)
-                        new_msg['accel_x_rolling_std'] = std_accels[0]
-                        new_msg['accel_y_rolling_std'] = std_accels[1]
-                        new_msg['accel_z_rolling_std'] = std_accels[2]
-                        mean_accels = np.mean(last_1000_accels, axis=0)
-                        new_msg['accel_x_rolling_mean'] = mean_accels[0]
-                        new_msg['accel_y_rolling_mean'] = mean_accels[1]
-                        new_msg['accel_z_rolling_mean'] = mean_accels[2]
-                        new_msg[accel_x] = msg[accel_x]
-                        new_msg[accel_y] = msg[accel_y]
-                        new_msg[accel_z] = msg[accel_z]
-                    if gyro_x in msg and gyro_y in msg and gyro_z in msg:
-                        last_1000_gyros[gyros_next_row, :] = [
-                            msg[gyro_x], msg[gyro_y], msg[gyro_z]
-                        ]
-                        gyros_next_row += 1
-                        gyros_next_row = gyros_next_row % buffer_len
-                        std_gyros = np.std(last_1000_gyros, axis=0)
-                        new_msg['gyro_x_rolling_std'] = std_gyros[0]
-                        new_msg['gyro_y_rolling_std'] = std_gyros[1]
-                        new_msg['gyro_z_rolling_std'] = std_gyros[2]
-                        mean_gyros = np.mean(last_1000_gyros, axis=0)
-                        new_msg['gyro_x_rolling_mean'] = mean_gyros[0]
-                        new_msg['gyro_y_rolling_mean'] = mean_gyros[1]
-                        new_msg['gyro_z_rolling_mean'] = mean_gyros[2]
-                        new_msg[gyro_x] = msg[gyro_x]
-                        new_msg[gyro_y] = msg[gyro_y]
-                        new_msg[gyro_z] = msg[gyro_z]
-                    timestamp = 'monotonic_timestamp_ns'
-                    if timestamp in msg:
-                        timestamp_sec = msg[timestamp] * 1e-9
-                        new_msg['monotonic_timestamp_sec'] = timestamp_sec
-                    entries.append((entry[0], entry[1], new_msg))
-            if 'CalcIMU' in self.data:
-                raise RuntimeError('CalcIMU is already a member of data.')
-            self.data['CalcIMU'] = entries
-
-    def calculate_signals(self):
-        """Calculate any derived signals for plotting.
-
-        See calculate_imu_signals for an example, but the basic idea is that
-        for any data that is read in from the logfile, we may want to calculate
-        some derived signals--possibly as simple as doing unit conversions,
-        or more complicated version where we do some filtering or the such.
-        The way this will work is that the calculate_* functions will, if the
-        raw data is available, calculate the derived signals and place them into
-        fake "messages" with an alias of "Calc*". E.g., we currently calculate
-        an overall magnitude for the accelerometer readings, which is helpful
-        to understanding how some internal filters work."""
-        self.calculate_imu_signals()
-        self.calculate_down_estimator_signals()
-
-    def extract_field(self, message: dict, field: str):
-        """Extracts a field with the given name from the message.
-
-        message will be a dictionary with field names as the keys and then
-        values, lists, or more dictionaries as the values. field is the full
-        path to the field to extract, with periods separating sub-messages."""
-        field_path = field.split('.')
-        value = message
-        for name in field_path:
-            # If the value wasn't populated in a given message, fill in
-            # NaN rather than crashing.
-            if name in value:
-                value = value[name]
-            else:
-                return None
-        # Catch NaNs and convert them to floats.
-        return float(value)
-
-    def plot_line(self, axes: matplotlib.axes.Axes, line: Line):
-        if not line.HasField('y_signal'):
-            raise ValueError("No y_channel specified for line.")
-        y_signal = line.y_signal
-        if not y_signal.channel in self.data:
-            raise ValueError("No channel alias " + y_signal.channel)
-        x_signal = line.x_signal if line.HasField('x_signal') else None
-        if x_signal is not None and not x_signal.channel in self.data:
-            raise ValueError("No channel alias " + x_signal.channel)
-        y_messages = self.data[y_signal.channel]
-        x_messages = self.data[
-            x_signal.channel] if x_signal is not None else None
-        if x_messages is not None and len(x_messages) != len(y_messages):
-            raise ValueError(
-                "X and Y signal lengths don't match. X channel is " +
-                x_signal.channel + " Y channel is " + y_signal.channel)
-        x_data = []
-        y_data = []
-        for ii in range(len(y_messages)):
-            y_entry = y_messages[ii]
-            if x_signal is None:
-                x_data.append(y_entry[0] * 1e-9)
-            else:
-                x_entry = x_messages[ii]
-                x_data.append(self.extract_field(x_entry[2], x_signal.field))
-            y_data.append(self.extract_field(y_entry[2], y_signal.field))
-            if x_data[-1] is None and y_data[-1] is not None:
-                raise ValueError(
-                    "Only one of the x and y signals is present. X " +
-                    x_signal.channel + "." + x_signal.field + " Y " +
-                    y_signal.channel + "." + y_signal.field)
-        label_name = y_signal.channel + "." + y_signal.field
-        axes.plot(x_data, y_data, marker='o', label=label_name)
-
-    def plot(self):
-        shared_axis = None
-        for figure_config in self.config.figure:
-            fig = plt.figure()
-            num_subplots = len(figure_config.axes)
-            for ii in range(num_subplots):
-                axes_config = figure_config.axes[ii]
-                share_axis = axes_config.share_x_axis
-                axes = fig.add_subplot(
-                    num_subplots,
-                    1,
-                    ii + 1,
-                    sharex=shared_axis if share_axis else None)
-                if share_axis and shared_axis is None:
-                    shared_axis = axes
-                for line in axes_config.line:
-                    self.plot_line(axes, line)
-                # Make the legend transparent so we can see behind it.
-                legend = axes.legend(framealpha=0.5, loc='upper right')
-                axes.set_xlabel(axes_config.xlabel)
-                axes.grid(True)
-                if axes_config.HasField("ylabel"):
-                    axes.set_ylabel(axes_config.ylabel)
-
-
-def main(argv):
-    parser = argparse.ArgumentParser(
-        description="Plot data from an aos logfile.")
-    parser.add_argument("--logfile",
-                        type=str,
-                        required=True,
-                        help="Path to the logfile to parse.")
-    parser.add_argument("--config",
-                        type=str,
-                        required=True,
-                        help="Name of the plot config to use.")
-    parser.add_argument("--config_dir",
-                        type=str,
-                        default="frc971/analysis/plot_configs",
-                        help="Directory to look for plot configs in.")
-    args = parser.parse_args(argv[1:])
-
-    if not os.path.isdir(args.config_dir):
-        print(args.config_dir + " is not a directory.")
-        return 1
-    config_path = os.path.join(args.config_dir, args.config)
-    if not os.path.isfile(config_path):
-        print(config_path +
-              " does not exist or is not a file--available configs are")
-        for file_name in os.listdir(args.config_dir):
-            print(os.path.basename(file_name))
-        return 1
-
-    config = PlotConfig()
-    with open(config_path) as config_file:
-        text_format.Merge(config_file.read(), config)
-
-    if not os.path.isfile(args.logfile):
-        print(args.logfile + " is not a file.")
-        return 1
-
-    reader = LogReader(args.logfile)
-
-    plotter = Plotter(config, reader)
-    plotter.process_logfile()
-    plotter.plot()
-    plt.show()
-
-    return 0
-
-
-if __name__ == '__main__':
-    sys.exit(main(sys.argv))
diff --git a/frc971/analysis/plot_config.proto b/frc971/analysis/plot_config.proto
deleted file mode 100644
index cd01f73..0000000
--- a/frc971/analysis/plot_config.proto
+++ /dev/null
@@ -1,64 +0,0 @@
-syntax = "proto2";
-
-package frc971.analysis;
-
-// Specification fo a Channel to pull from the logfile. The name and type will
-// be the full name/type of the channel to pull from the logfile. The alias is a
-// shorter, easier to type, name that the rest of the logfile will use to refer
-// to the channel.
-message Channel {
-  optional string name = 1;
-  optional string type = 2;
-  optional string alias = 3;
-}
-
-// A specification for a single signal within a Channel.
-message Signal {
-  // Alias for the channel to pull the signal from--this should match an alias
-  // specified in one of the Channels.
-  optional string channel = 1;
-  // Specification of the field to plot. Currently, this only supports simple
-  // submessages, using dots. To access, e.g., the "bar" member of the "foo"
-  // submessage, field would be "foo.bar". This does not currently support
-  // working with repeated fields.
-  optional string field = 2;
-}
-
-// A single line to plot.
-message Line {
-  // The signal to plot on the y-axis.
-  optional Signal y_signal = 1;
-  // If set, we will use this signal for the x-axis of the plot. By default, we
-  // will use the monotonic sent time of the message. This is helpful for both
-  // plotting against non-time based signals (e.g., plotting x/y robot position)
-  // as well as plotting against times other than the message sent time (e.g.,
-  // for the IMU where the sample capture time is separate from the actual
-  // sent time.
-  // Note that the x and y signals should have exactly the same number of
-  // entries--otherwise, we need to write logic to handle resampling one signal
-  // to a different rate.
-  optional Signal x_signal = 2;
-}
-
-// Message representing a single pyplot Axes, with specifications for exactly
-// which signals to show in the supplied subplot.
-message Axes {
-  repeated Line line = 1;
-  optional string ylabel = 2;
-  optional string xlabel = 3 [default = "Monotonic Time (sec)"];
-  // Whether to share an x-axis with all the other axes.
-  optional bool share_x_axis = 4 [default = true];
-}
-
-// Message representing a single pyplot figure.
-message Figure {
-  repeated Axes axes = 1;
-}
-
-// This configuration specifies what to plot when reading from a logfile.
-message PlotConfig {
-  // List of channels and their aliases to use in the plot.
-  repeated Channel channel = 1;
-  // Figures to plot.
-  repeated Figure figure = 2;
-}
diff --git a/frc971/analysis/plot_configs/down_estimator.pb b/frc971/analysis/plot_configs/down_estimator.pb
deleted file mode 100644
index 48cf2ef..0000000
--- a/frc971/analysis/plot_configs/down_estimator.pb
+++ /dev/null
@@ -1,187 +0,0 @@
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Status"
-  alias: "DrivetrainStatus"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.yaw"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.lateral_pitch"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.longitudinal_pitch"
-      }
-    }
-    ylabel: "rad"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.quaternion_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.quaternion_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.quaternion_z"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.quaternion_w"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_z"
-      }
-    }
-    ylabel: "m/s/s"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.velocity_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.velocity_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.velocity_z"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.position_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.position_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.position_z"
-      }
-    }
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "zeroing.gyro_x_average"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "zeroing.gyro_y_average"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "zeroing.gyro_z_average"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.expected_accel_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.expected_accel_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.expected_accel_z"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.gravity_magnitude"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcDrivetrainStatus"
-        field: "down_estimator.accel_x_rolling_mean"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcDrivetrainStatus"
-        field: "down_estimator.accel_y_rolling_mean"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcDrivetrainStatus"
-        field: "down_estimator.accel_z_rolling_mean"
-      }
-    }
-  }
-}
diff --git a/frc971/analysis/plot_configs/drivetrain.pb b/frc971/analysis/plot_configs/drivetrain.pb
deleted file mode 100644
index 0335da8..0000000
--- a/frc971/analysis/plot_configs/drivetrain.pb
+++ /dev/null
@@ -1,463 +0,0 @@
-channel {
-  name: "/aos"
-  type: "aos.JoystickState"
-  alias: "JoystickState"
-}
-channel {
-  name: "/aos"
-  type: "aos.RobotState"
-  alias: "RobotState"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Goal"
-  alias: "Goal"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Status"
-  alias: "Status"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Output"
-  alias: "Output"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.IMUValues"
-  alias: "IMU"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "JoystickState"
-        field: "test_mode"
-      }
-    }
-    line {
-      y_signal {
-        channel: "JoystickState"
-        field: "autonomous"
-      }
-    }
-    line {
-      y_signal {
-        channel: "RobotState"
-        field: "browned_out"
-      }
-    }
-    line {
-      y_signal {
-        channel: "JoystickState"
-        field: "enabled"
-      }
-    }
-    ylabel: "[bool]"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "RobotState"
-        field: "voltage_battery"
-      }
-    }
-    ylabel: "[V]"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "line_follow_logging.frozen"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Goal"
-        field: "quickturn"
-      }
-    }
-    ylabel: "[bool]"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "poly_drive_logging.ff_left_voltage"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "poly_drive_logging.ff_right_voltage"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Output"
-        field: "left_voltage"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Output"
-        field: "right_voltage"
-      }
-    }
-    ylabel: "[V]"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "theta"
-      }
-    }
-    ylabel: "[rad]"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "robot_speed"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "trajectory_logging.left_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "poly_drive_logging.goal_left_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "estimated_left_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "trajectory_logging.right_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "poly_drive_logging.goal_right_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "estimated_right_velocity"
-      }
-    }
-    ylabel: "[m/s]"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "gyro_x"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "gyro_y"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "gyro_z"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "total_acceleration"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "accelerometer_x"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "accelerometer_y"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "accelerometer_z"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.yaw"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.lateral_pitch"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.longitudinal_pitch"
-      }
-    }
-    ylabel: "rad"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.quaternion_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.quaternion_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.quaternion_z"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.quaternion_w"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.velocity_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.velocity_y"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.position_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "down_estimator.position_y"
-      }
-    }
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_x_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_y_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_z_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_x_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_y_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_z_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_x_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_y_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_z_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_x_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_y_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_z_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-}
diff --git a/frc971/analysis/plot_configs/gyro.pb b/frc971/analysis/plot_configs/gyro.pb
deleted file mode 100644
index 70c6480..0000000
--- a/frc971/analysis/plot_configs/gyro.pb
+++ /dev/null
@@ -1,238 +0,0 @@
-channel {
-  name: "/drivetrain"
-  type: "frc971.IMUValuesBatch"
-  alias: "IMU"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_x"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_y"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_z"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "total_acceleration"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accelerometer_x"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accelerometer_y"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accelerometer_z"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_x_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_y_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_z_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_x_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_y_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "accel_z_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "g"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_x_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_y_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_z_rolling_mean"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_x_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_y_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "gyro_z_rolling_std"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "CalcIMU"
-        field: "temperature"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "C"
-  }
-}
diff --git a/frc971/analysis/plot_configs/gyro_temp.pb b/frc971/analysis/plot_configs/gyro_temp.pb
deleted file mode 100644
index 02c8c3b..0000000
--- a/frc971/analysis/plot_configs/gyro_temp.pb
+++ /dev/null
@@ -1,21 +0,0 @@
-channel {
-  name: "/drivetrain"
-  type: "frc971.IMUValues"
-  alias: "IMU"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "IMU"
-        field: "temperature"
-      }
-      x_signal {
-        channel: "CalcIMU"
-        field: "monotonic_timestamp_sec"
-      }
-    }
-    ylabel: "C"
-  }
-}
diff --git a/frc971/analysis/plot_configs/localizer.pb b/frc971/analysis/plot_configs/localizer.pb
deleted file mode 100644
index 6181e11..0000000
--- a/frc971/analysis/plot_configs/localizer.pb
+++ /dev/null
@@ -1,322 +0,0 @@
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Status"
-  alias: "DrivetrainStatus"
-}
-channel {
-  name: "/drivetrain/truth"
-  type: "frc971.control_loops.drivetrain.Status"
-  alias: "DrivetrainTruthStatus"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Position"
-  alias: "DrivetrainPosition"
-}
-channel {
-  name: "/drivetrain"
-  type: "frc971.control_loops.drivetrain.Output"
-  alias: "DrivetrainOutput"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.y"
-      }
-      x_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainTruthStatus"
-        field: "y"
-      }
-      x_signal {
-        channel: "DrivetrainTruthStatus"
-        field: "x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "y"
-      }
-      x_signal {
-        channel: "DrivetrainStatus"
-        field: "x"
-      }
-    }
-    share_x_axis: false
-    xlabel: "x (m)"
-    ylabel: "y (m)"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.yaw"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.theta"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainTruthStatus"
-        field: "theta"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.theta"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.lateral_pitch"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.longitudinal_pitch"
-      }
-    }
-    ylabel: "rad"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.position_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.position_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainTruthStatus"
-        field: "x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainTruthStatus"
-        field: "y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.y"
-      }
-    }
-    ylabel: "m"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.velocity_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.velocity_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.longitudinal_velocity_offset"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.lateral_velocity"
-      }
-    }
-    ylabel: "m/s"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_x"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_y"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "down_estimator.accel_z"
-      }
-    }
-    ylabel: "m/s/s"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.left_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "trajectory_logging.right_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.left_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.right_velocity"
-      }
-    }
-    ylabel: "m/s"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainPosition"
-        field: "left_encoder"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainPosition"
-        field: "right_encoder"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.left_encoder"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.right_encoder"
-      }
-    }
-    ylabel: "m"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.angular_error"
-      }
-    }
-    ylabel: "rad / sec"
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainOutput"
-        field: "left_voltage"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainOutput"
-        field: "right_voltage"
-      }
-    }
-    ylabel: "V"
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "left_voltage_error"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "right_voltage_error"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.left_voltage_error"
-      }
-    }
-    line {
-      y_signal {
-        channel: "DrivetrainStatus"
-        field: "localizer.right_voltage_error"
-      }
-    }
-    ylabel: "V"
-  }
-}
diff --git a/frc971/analysis/plot_configs/turret_plot.pb b/frc971/analysis/plot_configs/turret_plot.pb
deleted file mode 100644
index 64c5f22..0000000
--- a/frc971/analysis/plot_configs/turret_plot.pb
+++ /dev/null
@@ -1,128 +0,0 @@
-channel {
-  name: "/roborio/aos"
-  type: "aos.JoystickState"
-  alias: "JoystickState"
-}
-channel {
-  name: "/superstructure"
-  type: "y2020.control_loops.superstructure.Status"
-  alias: "Status"
-}
-channel {
-  name: "/superstructure"
-  type: "y2020.control_loops.superstructure.Output"
-  alias: "Output"
-}
-channel {
-  name: "/superstructure"
-  type: "y2020.control_loops.superstructure.Position"
-  alias: "Position"
-}
-channel {
-  name: "/superstructure"
-  type: "y2020.control_loops.superstructure.Goal"
-  alias: "Goal"
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.goal_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.unprofiled_goal_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "aimer.turret_velocity"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.velocity"
-      }
-    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.goal_position"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.unprofiled_goal_position"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "aimer.turret_position"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.position"
-      }
-    }
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "aimer.aiming_for_inner_port"
-      }
-    }
-#    line {
-#      y_signal {
-#        channel: "JoystickState"
-#        field: "alliance"
-#      }
-#    }
-  }
-  axes {
-    line {
-      y_signal {
-        channel: "Status"
-        field: "aimer.shot_distance"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "aimer.target_distance"
-      }
-    }
-  }
-}
-
-figure {
-  axes {
-    line {
-      y_signal {
-        channel: "Output"
-        field: "turret_voltage"
-      }
-    }
-    line {
-      y_signal {
-        channel: "Status"
-        field: "turret.voltage_error"
-      }
-    }
-  }
-}
diff --git a/frc971/analysis/plot_test.py b/frc971/analysis/plot_test.py
deleted file mode 100644
index 1c57ae2..0000000
--- a/frc971/analysis/plot_test.py
+++ /dev/null
@@ -1,23 +0,0 @@
-#!/usr/bin/python3
-import unittest
-
-import matplotlib
-# Use a non-interactive backend so that the test can actually run...
-matplotlib.use('Agg')
-
-import frc971.analysis.plot
-
-
-class PlotterTest(unittest.TestCase):
-    def test_plotter(self):
-        """Basic test that makes sure that we can run the test without crashing."""
-        self.assertEqual(0,
-                         frc971.analysis.plot.main([
-                             "binary", "--logfile",
-                             "external/sample_logfile/file/log.fbs",
-                             "--config", "gyro.pb"
-                         ]))
-
-
-if __name__ == '__main__':
-    unittest.main()
diff --git a/frc971/analysis/py_log_reader.cc b/frc971/analysis/py_log_reader.cc
index 5b32ed6..6a6c767 100644
--- a/frc971/analysis/py_log_reader.cc
+++ b/frc971/analysis/py_log_reader.cc
@@ -1,6 +1,11 @@
 // This file provides a Python module for reading logfiles. See
 // log_reader_test.py for usage.
 //
+// NOTE: This code has not been maintained recently, and so is missing key
+// features to support reading multi-node logfiles (namely, it assumes the the
+// logfile is just a single file). Updating this code should not be difficult,
+// but hasn't been needed thus far.
+//
 // This reader works by having the user specify exactly what channels they want
 // data for. We then process the logfile and store all the data on that channel
 // into a list of timestamps + JSON message data. The user can then use an
diff --git a/frc971/codelab/BUILD b/frc971/codelab/BUILD
index d5c1c59..7565daf 100644
--- a/frc971/codelab/BUILD
+++ b/frc971/codelab/BUILD
@@ -15,7 +15,7 @@
         ":basic_output_fbs",
         ":basic_position_fbs",
         ":basic_status_fbs",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/events:shm_event_loop",
         "//aos/testing:googletest",
         "//frc971/control_loops:state_feedback_loop",
@@ -33,7 +33,7 @@
         ":basic_output_fbs",
         ":basic_position_fbs",
         ":basic_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
     ],
 )
 
diff --git a/frc971/codelab/basic.cc b/frc971/codelab/basic.cc
index 6144fed..8019445 100644
--- a/frc971/codelab/basic.cc
+++ b/frc971/codelab/basic.cc
@@ -4,8 +4,8 @@
 namespace codelab {
 
 Basic::Basic(::aos::EventLoop *event_loop, const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name) {}
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name) {}
 
 void Basic::RunIteration(const Goal *goal, const Position *position,
                          aos::Sender<Output>::Builder *output,
diff --git a/frc971/codelab/basic.h b/frc971/codelab/basic.h
index b75a87f..8748bc5 100644
--- a/frc971/codelab/basic.h
+++ b/frc971/codelab/basic.h
@@ -1,9 +1,8 @@
 #ifndef FRC971_CODELAB_BASIC_H_
 #define FRC971_CODELAB_BASIC_H_
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/time/time.h"
-
 #include "frc971/codelab/basic_goal_generated.h"
 #include "frc971/codelab/basic_output_generated.h"
 #include "frc971/codelab/basic_position_generated.h"
@@ -29,7 +28,7 @@
 //  2 channels are input channels: goal, position.
 //  2 channels are output channels: output, status.
 //
-// ::aos::controls::ControlLoop is a helper class that takes
+// ::frc971::controls::ControlLoop is a helper class that takes
 // all the channel types as template parameters and then calls
 // RunIteration() whenever a Position message is received.
 // It will pass in the Position message and most recent Goal message
@@ -52,7 +51,7 @@
 // that  would remove the challenge for future students), but we will go through
 // the code review process.
 class Basic
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Basic(::aos::EventLoop *event_loop,
                  const ::std::string &name = "/codelab");
diff --git a/frc971/codelab/basic_test.cc b/frc971/codelab/basic_test.cc
index 65ac625..9b22705 100644
--- a/frc971/codelab/basic_test.cc
+++ b/frc971/codelab/basic_test.cc
@@ -5,12 +5,12 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
 #include "aos/events/shm_event_loop.h"
 #include "frc971/codelab/basic_goal_generated.h"
 #include "frc971/codelab/basic_output_generated.h"
 #include "frc971/codelab/basic_position_generated.h"
 #include "frc971/codelab/basic_status_generated.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
 
@@ -81,10 +81,10 @@
   bool first_ = true;
 };
 
-class BasicControlLoopTest : public ::aos::testing::ControlLoopTest {
+class BasicControlLoopTest : public ::frc971::testing::ControlLoopTest {
  public:
   BasicControlLoopTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("frc971/codelab/config.json"),
             chrono::microseconds(5050)),
         test_event_loop_(MakeEventLoop("test")),
diff --git a/frc971/control_loops/BUILD b/frc971/control_loops/BUILD
index 11c93dc..3341402 100644
--- a/frc971/control_loops/BUILD
+++ b/frc971/control_loops/BUILD
@@ -4,6 +4,110 @@
 load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
 
 cc_library(
+    name = "control_loop_test",
+    testonly = True,
+    srcs = [
+        "control_loop_test.cc",
+    ],
+    hdrs = [
+        "control_loop_test.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos:flatbuffers",
+        "//aos:json_to_flatbuffer",
+        "//aos/events:simulated_event_loop",
+        "//aos/testing:googletest",
+        "//aos/testing:test_logging",
+        "//aos/time",
+        "//frc971/input:joystick_state_fbs",
+        "//frc971/input:robot_state_fbs",
+    ],
+)
+
+cc_library(
+    name = "polytope",
+    hdrs = [
+        "polytope.h",
+    ],
+    deps = [
+        "@org_tuxfamily_eigen//:eigen",
+    ] + select({
+        "@platforms//os:linux": [
+            "//aos/logging",
+            "//third_party/cddlib",
+            "@com_github_google_glog//:glog",
+        ],
+        "//conditions:default": [],
+    }),
+)
+
+cc_test(
+    name = "polytope_test",
+    srcs = [
+        "polytope_test.cc",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        ":polytope",
+        "//aos/testing:googletest",
+        "//aos/testing:test_logging",
+        "@org_tuxfamily_eigen//:eigen",
+    ],
+)
+
+cc_library(
+    name = "control_loop",
+    srcs = [
+        "control_loop.cc",
+        "control_loop-tmpl.h",
+    ],
+    hdrs = [
+        "control_loop.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/events:event_loop",
+        "//aos/events:shm_event_loop",
+        "//aos/logging",
+        "//aos/time",
+        "//aos/util:log_interval",
+        "//frc971/input:joystick_state_fbs",
+        "//frc971/input:robot_state_fbs",
+    ],
+)
+
+cc_library(
+    name = "quaternion_utils",
+    srcs = [
+        "quaternion_utils.cc",
+    ],
+    hdrs = [
+        "quaternion_utils.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "@com_github_google_glog//:glog",
+        "@org_tuxfamily_eigen//:eigen",
+    ],
+)
+
+cc_test(
+    name = "quarternion_utils_test",
+    srcs = [
+        "quaternion_utils_test.cc",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        ":quaternion_utils",
+        "//aos/testing:googletest",
+        "//aos/testing:random_seed",
+        "@com_github_google_glog//:glog",
+        "@org_tuxfamily_eigen//:eigen",
+    ],
+)
+
+cc_library(
     name = "team_number_test_environment",
     testonly = True,
     srcs = [
@@ -130,7 +234,7 @@
         "//conditions:default": [],
     }),
     deps = [
-        "//aos/controls:polytope",
+        "//frc971/control_loops:polytope",
         "@org_tuxfamily_eigen//:eigen",
     ],
 )
@@ -146,7 +250,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":coerce_goal",
-        "//aos/controls:polytope",
+        "//frc971/control_loops:polytope",
         "//aos/testing:googletest",
         "@org_tuxfamily_eigen//:eigen",
     ],
@@ -176,7 +280,7 @@
         ":c2d",
         ":state_feedback_loop",
         "//aos:macros",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "@org_tuxfamily_eigen//:eigen",
     ],
@@ -263,7 +367,7 @@
         ":profiled_subsystem_fbs",
         ":simple_capped_state_feedback_loop",
         ":state_feedback_loop",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/util:trapezoid_profile",
         "//frc971/zeroing",
     ],
@@ -509,7 +613,7 @@
         ":static_zeroing_single_dof_profiled_subsystem_test_pot_and_absolute_position_fbs",
         ":static_zeroing_single_dof_profiled_subsystem_test_subsystem_goal_fbs",
         ":static_zeroing_single_dof_profiled_subsystem_test_subsystem_output_fbs",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
     ],
 )
diff --git a/frc971/control_loops/coerce_goal.cc b/frc971/control_loops/coerce_goal.cc
index 6fdc70f..6e1dcf4 100644
--- a/frc971/control_loops/coerce_goal.cc
+++ b/frc971/control_loops/coerce_goal.cc
@@ -1,7 +1,7 @@
 #include "frc971/control_loops/coerce_goal.h"
 
 #include "Eigen/Dense"
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/polytope.h"
 
 namespace frc971 {
 namespace control_loops {}  // namespace control_loops
diff --git a/frc971/control_loops/coerce_goal.h b/frc971/control_loops/coerce_goal.h
index b682b85..1847682 100644
--- a/frc971/control_loops/coerce_goal.h
+++ b/frc971/control_loops/coerce_goal.h
@@ -2,15 +2,14 @@
 #define FRC971_CONTROL_LOOPS_COERCE_GOAL_H_
 
 #include "Eigen/Dense"
-
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/polytope.h"
 
 namespace frc971 {
 namespace control_loops {
 
 template <typename Scalar = double>
 Eigen::Matrix<Scalar, 2, 1> DoCoerceGoal(
-    const aos::controls::HVPolytope<2, 4, 4, Scalar> &region,
+    const frc971::controls::HVPolytope<2, 4, 4, Scalar> &region,
     const Eigen::Matrix<Scalar, 1, 2> &K, Scalar w,
     const Eigen::Matrix<Scalar, 2, 1> &R, bool *is_inside);
 
@@ -20,7 +19,7 @@
 // finds a point that is inside the region and closest to the line.
 template <typename Scalar = double>
 static inline Eigen::Matrix<Scalar, 2, 1> CoerceGoal(
-    const aos::controls::HVPolytope<2, 4, 4, Scalar> &region,
+    const frc971::controls::HVPolytope<2, 4, 4, Scalar> &region,
     const Eigen::Matrix<Scalar, 1, 2> &K, Scalar w,
     const Eigen::Matrix<Scalar, 2, 1> &R) {
   return DoCoerceGoal(region, K, w, R, nullptr);
@@ -28,7 +27,7 @@
 
 template <typename Scalar>
 Eigen::Matrix<Scalar, 2, 1> DoCoerceGoal(
-    const aos::controls::HVPolytope<2, 4, 4, Scalar> &region,
+    const frc971::controls::HVPolytope<2, 4, 4, Scalar> &region,
     const Eigen::Matrix<Scalar, 1, 2> &K, Scalar w,
     const Eigen::Matrix<Scalar, 2, 1> &R, bool *is_inside) {
   if (region.IsInside(R)) {
diff --git a/frc971/control_loops/coerce_goal_test.cc b/frc971/control_loops/coerce_goal_test.cc
index ae04d6c..acdee9f 100644
--- a/frc971/control_loops/coerce_goal_test.cc
+++ b/frc971/control_loops/coerce_goal_test.cc
@@ -2,7 +2,7 @@
 
 #include <unistd.h>
 
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/polytope.h"
 #include "gtest/gtest.h"
 
 namespace frc971 {
@@ -10,8 +10,8 @@
 
 namespace {
 
-aos::controls::HVPolytope<2, 4, 4> MakeBox(double x1_min, double x1_max,
-                                           double x2_min, double x2_max) {
+frc971::controls::HVPolytope<2, 4, 4> MakeBox(double x1_min, double x1_max,
+                                              double x2_min, double x2_max) {
   Eigen::Matrix<double, 4, 2> box_H;
   box_H << /*[[*/ 1.0, 0.0 /*]*/,
       /*[*/ -1.0, 0.0 /*]*/,
@@ -22,21 +22,20 @@
       /*[*/ -x1_min /*]*/,
       /*[*/ x2_max /*]*/,
       /*[*/ -x2_min /*]]*/;
-  aos::controls::HPolytope<2> t_poly(box_H, box_k);
-  return aos::controls::HVPolytope<2, 4, 4>(t_poly.H(), t_poly.k(),
-                                            t_poly.Vertices());
+  frc971::controls::HPolytope<2> t_poly(box_H, box_k);
+  return frc971::controls::HVPolytope<2, 4, 4>(t_poly.H(), t_poly.k(),
+                                               t_poly.Vertices());
 }
 }  // namespace
 
 class CoerceGoalTest : public ::testing::Test {
  public:
-  void SetUp() override { aos::controls::HPolytope<2>::Init(); }
+  void SetUp() override { frc971::controls::HPolytope<2>::Init(); }
   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 };
 
-
 TEST_F(CoerceGoalTest, Inside) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << /*[[*/ 1, -1 /*]]*/;
@@ -52,7 +51,7 @@
 }
 
 TEST_F(CoerceGoalTest, LineOutside) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   // Make a line equivalent to y = -x, which does not pass through the box and
   // is nearest the box at (1, 1).
@@ -76,7 +75,7 @@
 }
 
 TEST_F(CoerceGoalTest, GoalOutsideLineInsideThroughOrigin) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << 1, -1;
@@ -92,7 +91,7 @@
 }
 
 TEST_F(CoerceGoalTest, GoalOutsideLineNotThroughOrigin) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << 1, 1;
@@ -108,7 +107,7 @@
 }
 
 TEST_F(CoerceGoalTest, GoalOutsideLineThroughVertex) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << 1, -1;
@@ -124,7 +123,7 @@
 }
 
 TEST_F(CoerceGoalTest, LineAndGoalOutside) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(3, 4, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(3, 4, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << 1, -1;
@@ -140,7 +139,7 @@
 }
 
 TEST_F(CoerceGoalTest, LineThroughEdgeOfBox) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(0, 4, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(0, 4, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << -1, 1;
@@ -156,7 +155,7 @@
 }
 
 TEST_F(CoerceGoalTest, PerpendicularLine) {
-  aos::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
+  frc971::controls::HVPolytope<2, 4, 4> box = MakeBox(1, 2, 1, 2);
 
   Eigen::Matrix<double, 1, 2> K;
   K << 1, 1;
diff --git a/aos/controls/control_loop-tmpl.h b/frc971/control_loops/control_loop-tmpl.h
similarity index 98%
rename from aos/controls/control_loop-tmpl.h
rename to frc971/control_loops/control_loop-tmpl.h
index 349a55c..f6fd0af 100644
--- a/aos/controls/control_loop-tmpl.h
+++ b/frc971/control_loops/control_loop-tmpl.h
@@ -3,7 +3,7 @@
 
 #include "aos/logging/logging.h"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 // TODO(aschuh): Tests.
@@ -91,4 +91,4 @@
 }
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
diff --git a/frc971/control_loops/control_loop.cc b/frc971/control_loops/control_loop.cc
new file mode 100644
index 0000000..99c005a
--- /dev/null
+++ b/frc971/control_loops/control_loop.cc
@@ -0,0 +1,7 @@
+#include "frc971/control_loops/control_loop.h"
+
+namespace frc971 {
+namespace controls {
+
+}  // namespace controls
+}  // namespace frc971
diff --git a/aos/controls/control_loop.h b/frc971/control_loops/control_loop.h
similarity index 94%
rename from aos/controls/control_loop.h
rename to frc971/control_loops/control_loop.h
index efe3493..741b32f 100644
--- a/aos/controls/control_loop.h
+++ b/frc971/control_loops/control_loop.h
@@ -12,7 +12,7 @@
 #include "frc971/input/joystick_state_generated.h"
 #include "frc971/input/robot_state_generated.h"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 // Control loops run this often, "starting" at time 0.
@@ -26,7 +26,7 @@
           class OutputType>
 class ControlLoop {
  public:
-  ControlLoop(EventLoop *event_loop, const ::std::string &name)
+  ControlLoop(aos::EventLoop *event_loop, const ::std::string &name)
       : event_loop_(event_loop), name_(name) {
     output_sender_ = event_loop_->MakeSender<OutputType>(name_);
     status_sender_ = event_loop_->MakeSender<StatusType>(name_);
@@ -74,7 +74,7 @@
   // Runs one cycle of the loop.
   void IteratePosition(const PositionType &position);
 
-  EventLoop *event_loop() { return event_loop_; }
+  aos::EventLoop *event_loop() { return event_loop_; }
 
   // Returns the position context.  This is only valid inside the RunIteration
   // method.
@@ -105,7 +105,7 @@
       ::std::chrono::milliseconds(100);
 
   // Pointer to the queue group
-  EventLoop *event_loop_;
+  aos::EventLoop *event_loop_;
   ::std::string name_;
 
   ::aos::Sender<OutputType> output_sender_;
@@ -135,8 +135,8 @@
 };
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
 
-#include "aos/controls/control_loop-tmpl.h"  // IWYU pragma: export
+#include "frc971/control_loops/control_loop-tmpl.h"  // IWYU pragma: export
 
 #endif
diff --git a/frc971/control_loops/control_loop_test.cc b/frc971/control_loops/control_loop_test.cc
new file mode 100644
index 0000000..e28f595
--- /dev/null
+++ b/frc971/control_loops/control_loop_test.cc
@@ -0,0 +1,10 @@
+#include "frc971/control_loops/control_loop_test.h"
+
+#include <chrono>
+
+namespace frc971 {
+namespace testing {
+
+
+}  // namespace testing
+}  // namespace frc971
diff --git a/aos/controls/control_loop_test.h b/frc971/control_loops/control_loop_test.h
similarity index 88%
rename from aos/controls/control_loop_test.h
rename to frc971/control_loops/control_loop_test.h
index 2a892fa..de9d4cd 100644
--- a/aos/controls/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -13,7 +13,7 @@
 #include "frc971/input/robot_state_generated.h"
 #include "gtest/gtest.h"
 
-namespace aos {
+namespace frc971 {
 namespace testing {
 
 // Handles setting up the environment that all control loops need to actually
@@ -25,18 +25,18 @@
 class ControlLoopTestTemplated : public TestBaseClass {
  public:
   ControlLoopTestTemplated(
-      FlatbufferDetachedBuffer<Configuration> configuration,
+      aos::FlatbufferDetachedBuffer<aos::Configuration> configuration,
       ::std::chrono::nanoseconds dt = kTimeTick)
       : configuration_(std::move(configuration)),
         event_loop_factory_(&configuration_.message()),
         dt_(dt),
         robot_status_event_loop_(MakeEventLoop(
             "robot_status",
-            configuration::MultiNode(event_loop_factory_.configuration())
-                ? configuration::GetNode(event_loop_factory_.configuration(),
-                                         "roborio")
+            aos::configuration::MultiNode(event_loop_factory_.configuration())
+                ? aos::configuration::GetNode(
+                      event_loop_factory_.configuration(), "roborio")
                 : nullptr)) {
-    testing::EnableTestLogging();
+    aos::testing::EnableTestLogging();
     robot_state_sender_ =
         robot_status_event_loop_->MakeSender<::aos::RobotState>("/aos");
     joystick_state_sender_ =
@@ -82,7 +82,7 @@
   }
 
   ::std::unique_ptr<::aos::EventLoop> MakeEventLoop(
-      std::string_view name, const Node *node = nullptr) {
+      std::string_view name, const aos::Node *node = nullptr) {
     return event_loop_factory_.MakeEventLoop(name, node);
   }
 
@@ -90,7 +90,7 @@
     event_loop_factory_.set_send_delay(send_delay);
   }
 
-  void RunFor(monotonic_clock::duration duration) {
+  void RunFor(aos::monotonic_clock::duration duration) {
     event_loop_factory_.RunFor(duration);
   }
 
@@ -100,11 +100,11 @@
 
   ::std::chrono::nanoseconds dt() const { return dt_; }
 
-  const Configuration *configuration() const {
+  const aos::Configuration *configuration() const {
     return &configuration_.message();
   }
 
-  SimulatedEventLoopFactory *event_loop_factory() {
+  aos::SimulatedEventLoopFactory *event_loop_factory() {
     return &event_loop_factory_;
   }
 
@@ -156,9 +156,9 @@
   static constexpr ::std::chrono::microseconds kTimeTick{5000};
   static constexpr ::std::chrono::milliseconds kDSPacketTime{20};
 
-  FlatbufferDetachedBuffer<Configuration> configuration_;
+  aos::FlatbufferDetachedBuffer<aos::Configuration> configuration_;
 
-  SimulatedEventLoopFactory event_loop_factory_;
+  aos::SimulatedEventLoopFactory event_loop_factory_;
 
   const ::std::chrono::nanoseconds dt_;
 
@@ -191,6 +191,6 @@
     ControlLoopTestTemplated<TestBaseClass>::kDSPacketTime;
 
 }  // namespace testing
-}  // namespace aos
+}  // namespace frc971
 
 #endif  // AOS_CONTROLS_CONTROL_LOOP_TEST_H_
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index ec480c0..f44abe0 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -315,8 +315,8 @@
         ":localizer",
         ":spline_goal_fbs",
         "//aos:math",
-        "//aos/controls:control_loop",
-        "//aos/controls:polytope",
+        "//frc971/control_loops:control_loop",
+        "//frc971/control_loops:polytope",
         "//frc971/input:robot_state_fbs",
         "//aos/util:log_interval",
         "//aos/util:trapezoid_profile",
@@ -344,7 +344,7 @@
         ":drivetrain_states",
         ":gear",
         "//aos:math",
-        "//aos/controls:polytope",
+        "//frc971/control_loops:polytope",
         "//frc971/control_loops:coerce_goal",
         "//frc971/control_loops:control_loops_fbs",
         ":spline_goal_fbs",
@@ -425,7 +425,7 @@
         ":spline_goal_fbs",
         ":splinedrivetrain",
         ":ssdrivetrain",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/util:log_interval",
         "//frc971/control_loops:runge_kutta",
         "//frc971/queues:gyro_fbs",
@@ -497,7 +497,7 @@
         ":drivetrain_position_fbs",
         ":drivetrain_output_fbs",
         ":drivetrain_test_lib",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/events/logging:log_writer",
         "//aos/testing:googletest",
         "//frc971/queues:gyro_fbs",
@@ -728,7 +728,7 @@
     deps = [
         ":drivetrain_config",
         ":drivetrain_status_fbs",
-        "//aos/controls:quaternion_utils",
+        "//frc971/control_loops:quaternion_utils",
         "//aos/events:event_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:runge_kutta",
@@ -746,7 +746,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":drivetrain_test_lib",
-        "//aos/controls:quaternion_utils",
+        "//frc971/control_loops:quaternion_utils",
         "//aos/testing:googletest",
         "//aos/testing:random_seed",
         "//frc971/control_loops/drivetrain:improved_down_estimator",
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 91f1513..5242550 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -2,10 +2,11 @@
 
 #include <sched.h>
 #include <stdio.h>
+
 #include <cmath>
 #include <memory>
-#include "Eigen/Dense"
 
+#include "Eigen/Dense"
 #include "aos/logging/logging.h"
 #include "frc971/control_loops/drivetrain/down_estimator.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
@@ -47,7 +48,7 @@
       right_high_requested_(dt_config_.default_high_gear) {
   last_voltage_.setZero();
   last_last_voltage_.setZero();
-  aos::controls::HPolytope<0>::Init();
+  frc971::controls::HPolytope<0>::Init();
   event_loop->OnRun([this]() {
     // On the first fetch, make sure that we are caught all the way up to the
     // present.
@@ -300,8 +301,8 @@
                                ::aos::EventLoop *event_loop,
                                LocalizerInterface *localizer,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       dt_config_(dt_config),
       filters_(dt_config, event_loop, localizer),
       dt_openloop_(dt_config_, filters_.kf()),
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index 325715f..efaf53d 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -2,9 +2,8 @@
 #define FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
 
 #include "Eigen/Dense"
-
-#include "aos/controls/control_loop.h"
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/polytope.h"
 #include "aos/util/log_interval.h"
 #include "frc971/control_loops/control_loops_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
@@ -142,7 +141,7 @@
 };
 
 class DrivetrainLoop
-    : public aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   // Note that we only actually store N - 1 splines, since we need to keep one
   // fetcher free to check whether there are any new splines.
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index 64fb0b8..749b998 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -3,16 +3,11 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
-#include "aos/controls/polytope.h"
 #include "aos/events/event_loop.h"
 #include "aos/events/logging/log_writer.h"
 #include "aos/time/time.h"
-#include "gflags/gflags.h"
-#include "gtest/gtest.h"
-#include "gmock/gmock.h"
-
 #include "frc971/control_loops/coerce_goal.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/drivetrain/drivetrain.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
 #include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
@@ -20,9 +15,13 @@
 #include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
-#include "frc971/control_loops/drivetrain/trajectory_generator.h"
 #include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/control_loops/drivetrain/trajectory_generator.h"
+#include "frc971/control_loops/polytope.h"
 #include "frc971/queues/gyro_generated.h"
+#include "gflags/gflags.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
 
 DEFINE_string(output_file, "",
               "If set, logs all channels to the provided logfile.");
@@ -35,10 +34,10 @@
 namespace chrono = ::std::chrono;
 using ::aos::monotonic_clock;
 
-class DrivetrainTest : public ::aos::testing::ControlLoopTest {
+class DrivetrainTest : public ::frc971::testing::ControlLoopTest {
  protected:
   DrivetrainTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig(
                 "frc971/control_loops/drivetrain/simulation_config.json"),
             GetTestDrivetrainConfig().dt),
@@ -581,7 +580,6 @@
   VerifyNearSplineGoal();
 }
 
-
 // Tests that we can drive a spline backwards.
 TEST_F(DrivetrainTest, SplineSimpleBackwards) {
   SetEnabled(true);
@@ -741,7 +739,6 @@
     EXPECT_FALSE(CHECK_NOTNULL(drivetrain_status_fetcher_->trajectory_logging())
                      ->has_y());
   }
-
 }
 
 // Tests that a spline can't be restarted.
@@ -869,8 +866,8 @@
 }
 
 INSTANTIATE_TEST_SUITE_P(DriveSplinesForwardsAndBackwards,
-                        DrivetrainBackwardsParamTest,
-                        ::testing::Values(false, true));
+                         DrivetrainBackwardsParamTest,
+                         ::testing::Values(false, true));
 
 // Tests that simple spline converges when it starts to the side of where it
 // thinks.
diff --git a/frc971/control_loops/drivetrain/drivetrain_status.fbs b/frc971/control_loops/drivetrain/drivetrain_status.fbs
index fe691ed..fd3ff0e 100644
--- a/frc971/control_loops/drivetrain/drivetrain_status.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_status.fbs
@@ -190,10 +190,15 @@
   // in the zeroing.
   number_of_zeroes:int (id: 2);
 
-  // Current zeroing values beind used for each gyro axis, in rad / sec.
+  // Current zeroing values being used for each gyro axis, in rad / sec.
   gyro_x_average:float (id: 3);
   gyro_y_average:float (id: 4);
   gyro_z_average:float (id: 5);
+
+  // Current zeroing values being used for each accelerometer axis, in m / s^2.
+  accel_x_average:float (id: 6);
+  accel_y_average:float (id: 7);
+  accel_z_average:float (id: 8);
 }
 
 table Status {
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator.cc b/frc971/control_loops/drivetrain/improved_down_estimator.cc
index 56e7536..2c129f7 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator.cc
+++ b/frc971/control_loops/drivetrain/improved_down_estimator.cc
@@ -2,8 +2,7 @@
 
 #include "Eigen/Dense"
 #include "Eigen/Geometry"
-
-#include "aos/controls/quaternion_utils.h"
+#include "frc971/control_loops/quaternion_utils.h"
 
 namespace frc971 {
 namespace control_loops {
@@ -80,7 +79,7 @@
 
   // We now have the sigma points after the model update.
   // Compute the mean of the transformed sigma point
-  X_hat_ = Eigen::Quaternion<double>(aos::controls::QuaternionMean(Y));
+  X_hat_ = Eigen::Quaternion<double>(frc971::controls::QuaternionMean(Y));
 
   // And the covariance.
   Eigen::Matrix<double, 3, 2 * 3 + 1> Wprime;
@@ -159,7 +158,7 @@
 
   // Update X_hat and the covariance P
   X_hat_ = X_hat_ * Eigen::Quaternion<double>(
-                        aos::controls::ToQuaternionFromRotationVector(
+                        frc971::controls::ToQuaternionFromRotationVector(
                             K * (measurement - Z_hat_)));
   P_ = P_prior - K * P_vv * K.transpose();
 }
@@ -215,7 +214,7 @@
   for (int i = 0; i < 7; ++i) {
     // Compute the error vector for each sigma point.
     Eigen::Matrix<double, 3, 1> Wprimei =
-        aos::controls::ToRotationVectorFromQuaternion(
+        frc971::controls::ToRotationVectorFromQuaternion(
             Eigen::Quaternion<double>(mean).conjugate() *
             Eigen::Quaternion<double>(points.col(i)));
     // Now, compute the contribution of this sigma point to P_prior.
@@ -241,7 +240,7 @@
   Eigen::Matrix<double, 4, 3 * 2 + 1> X;
   for (int i = 0; i < 3; ++i) {
     Eigen::Quaternion<double> perturbation(
-        aos::controls::ToQuaternionFromRotationVector(S.col(i), M_PI_2));
+        frc971::controls::ToQuaternionFromRotationVector(S.col(i), M_PI_2));
 
     X.col(i * 2) = (mean * perturbation).coeffs();
     X.col(i * 2 + 1) = (mean * perturbation.conjugate()).coeffs();
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
index 9894f68..8aed6b2 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
+++ b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
@@ -3,7 +3,7 @@
 #include <Eigen/Geometry>
 #include <random>
 
-#include "aos/controls/quaternion_utils.h"
+#include "frc971/control_loops/quaternion_utils.h"
 #include "aos/testing/random_seed.h"
 #include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
 #include "frc971/control_loops/runge_kutta.h"
@@ -235,7 +235,7 @@
       drivetrain::GenerateSigmaPoints(mean, covariance);
 
   const Eigen::Matrix<double, 4, 1> calculated_mean =
-      aos::controls::QuaternionMean(vectors);
+      frc971::controls::QuaternionMean(vectors);
 
   VLOG(1) << "actual mean: " << mean.coeffs();
   VLOG(1) << "calculated mean: " << calculated_mean;
@@ -266,7 +266,7 @@
       drivetrain::GenerateSigmaPoints(mean, covariance);
 
   const Eigen::Matrix<double, 4, 1> calculated_mean =
-      aos::controls::QuaternionMean(vectors);
+      frc971::controls::QuaternionMean(vectors);
 
   Eigen::Matrix<double, 3, 3 * 2 + 1> Wprime;
   Eigen::Matrix<double, 3, 3> calculated_covariance =
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.h b/frc971/control_loops/drivetrain/polydrivetrain.h
index fe733bb..aea030e 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.h
+++ b/frc971/control_loops/drivetrain/polydrivetrain.h
@@ -2,7 +2,7 @@
 #define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_H_
 
 #include "aos/commonmath.h"
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/polytope.h"
 #include "frc971/control_loops/coerce_goal.h"
 #include "frc971/control_loops/drivetrain/gear.h"
 #ifdef __linux__
@@ -80,7 +80,7 @@
 
   StateFeedbackLoop<7, 2, 4, Scalar> *kf_;
 
-  const ::aos::controls::HVPolytope<2, 4, 4, Scalar> U_Poly_;
+  const ::frc971::controls::HVPolytope<2, 4, 4, Scalar> U_Poly_;
 
   ::std::unique_ptr<StateFeedbackLoop<2, 2, 2, Scalar>> loop_;
 
@@ -340,12 +340,12 @@
       const Scalar equality_w = kZero;
 
       // Construct a constraint on R by manipulating the constraint on U
-      ::aos::controls::HVPolytope<2, 4, 4, Scalar> R_poly_hv(
+      ::frc971::controls::HVPolytope<2, 4, 4, Scalar> R_poly_hv(
           U_Poly_.static_H() * (loop_->controller().K() + FF),
           U_Poly_.static_k() +
               U_Poly_.static_H() * loop_->controller().K() * loop_->X_hat(),
           (loop_->controller().K() + FF).inverse() *
-              ::aos::controls::ShiftPoints<2, 4, Scalar>(
+              ::frc971::controls::ShiftPoints<2, 4, Scalar>(
                   U_Poly_.StaticVertices(),
                   loop_->controller().K() * loop_->X_hat()));
 
diff --git a/frc971/control_loops/drivetrain/ssdrivetrain.cc b/frc971/control_loops/drivetrain/ssdrivetrain.cc
index 3e58d09..594175c 100644
--- a/frc971/control_loops/drivetrain/ssdrivetrain.cc
+++ b/frc971/control_loops/drivetrain/ssdrivetrain.cc
@@ -1,8 +1,7 @@
 #include "frc971/control_loops/drivetrain/ssdrivetrain.h"
 
 #include "aos/commonmath.h"
-#include "aos/controls/polytope.h"
-
+#include "frc971/control_loops/polytope.h"
 #include "frc971/control_loops/coerce_goal.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
 #include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
@@ -33,10 +32,10 @@
           (Eigen::Matrix<double, 2, 4>() << /*[[*/ 1.0, 1.0, -1.0, -1.0 /*]*/,
            /*[*/ -1.0, 1.0, 1.0, -1.0 /*]*/)
               .finished()),
-      linear_profile_(::aos::controls::kLoopFrequency),
-      angular_profile_(::aos::controls::kLoopFrequency),
+      linear_profile_(::frc971::controls::kLoopFrequency),
+      angular_profile_(::frc971::controls::kLoopFrequency),
       localizer_(localizer) {
-  ::aos::controls::HPolytope<0>::Init();
+  ::frc971::controls::HPolytope<0>::Init();
   T_ << 1, 1, 1, -1;
   T_inverse_ = T_.inverse();
   unprofiled_goal_.setZero();
@@ -87,13 +86,13 @@
       error_K * Eigen::Matrix<double, 2, 1>(kf_->X_hat(kLeftError),
                                             kf_->X_hat(kRightError));
 
-  const ::aos::controls::HVPolytope<2, 4, 4> pos_poly_hv(
+  const ::frc971::controls::HVPolytope<2, 4, 4> pos_poly_hv(
       U_poly_.static_H() * position_K * T_,
       U_poly_.static_H() *
               (-velocity_K * velocity_error + U_integral - kf_->ff_U()) +
           (U_poly_.static_k() * max_voltage_),
       (position_K * T_).inverse() *
-          ::aos::controls::ShiftPoints<2, 4, double>(
+          ::frc971::controls::ShiftPoints<2, 4, double>(
               (U_poly_.StaticVertices() * max_voltage_),
               -velocity_K * velocity_error + U_integral - kf_->ff_U()));
 
diff --git a/frc971/control_loops/drivetrain/ssdrivetrain.h b/frc971/control_loops/drivetrain/ssdrivetrain.h
index d83473d..be42abf 100644
--- a/frc971/control_loops/drivetrain/ssdrivetrain.h
+++ b/frc971/control_loops/drivetrain/ssdrivetrain.h
@@ -2,10 +2,9 @@
 #define FRC971_CONTROL_LOOPS_DRIVETRAIN_SSDRIVETRAIN_H_
 
 #include "aos/commonmath.h"
-#include "aos/controls/control_loop.h"
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/polytope.h"
 #include "aos/util/trapezoid_profile.h"
-
 #include "frc971/control_loops/coerce_goal.h"
 #include "frc971/control_loops/control_loops_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
@@ -56,7 +55,7 @@
 
   // Reprsents +/- full power on each motor in U-space, aka the square from
   // (-12, -12) to (12, 12).
-  const ::aos::controls::HVPolytope<2, 4, 4> U_poly_;
+  const ::frc971::controls::HVPolytope<2, 4, 4> U_poly_;
 
   // multiplying by T converts [left_error, right_error] to
   // [left_right_error_difference, total_distance_error].
diff --git a/frc971/control_loops/hybrid_state_feedback_loop.h b/frc971/control_loops/hybrid_state_feedback_loop.h
index f033a89..4dab950 100644
--- a/frc971/control_loops/hybrid_state_feedback_loop.h
+++ b/frc971/control_loops/hybrid_state_feedback_loop.h
@@ -11,7 +11,7 @@
 #include "Eigen/Dense"
 #include "unsupported/Eigen/MatrixFunctions"
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/logging/logging.h"
 #include "aos/macros.h"
 #include "frc971/control_loops/c2d.h"
diff --git a/aos/controls/polytope.h b/frc971/control_loops/polytope.h
similarity index 98%
rename from aos/controls/polytope.h
rename to frc971/control_loops/polytope.h
index 28f011e..1d707d4 100644
--- a/aos/controls/polytope.h
+++ b/frc971/control_loops/polytope.h
@@ -10,7 +10,7 @@
 #include "glog/logging.h"
 #endif  // __linux__
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 // A number_of_dimensions dimensional polytope.
@@ -235,6 +235,6 @@
 #endif  // __linux__
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
 
 #endif  // AOS_CONTROLS_POLYTOPE_H_
diff --git a/aos/controls/polytope_test.cc b/frc971/control_loops/polytope_test.cc
similarity index 97%
rename from aos/controls/polytope_test.cc
rename to frc971/control_loops/polytope_test.cc
index d7ec5e5..849438d 100644
--- a/aos/controls/polytope_test.cc
+++ b/frc971/control_loops/polytope_test.cc
@@ -1,4 +1,4 @@
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/polytope.h"
 
 #include <vector>
 
@@ -8,7 +8,7 @@
 
 #include "aos/testing/test_logging.h"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 class HPolytopeTest : public ::testing::Test {
@@ -99,4 +99,4 @@
 }
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
diff --git a/frc971/control_loops/profiled_subsystem.h b/frc971/control_loops/profiled_subsystem.h
index d16c17d..6780e3b 100644
--- a/frc971/control_loops/profiled_subsystem.h
+++ b/frc971/control_loops/profiled_subsystem.h
@@ -8,7 +8,7 @@
 
 #include "Eigen/Dense"
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/util/trapezoid_profile.h"
 #include "frc971/constants.h"
 #include "frc971/control_loops/control_loops_generated.h"
diff --git a/aos/controls/quaternion_utils.cc b/frc971/control_loops/quaternion_utils.cc
similarity index 97%
rename from aos/controls/quaternion_utils.cc
rename to frc971/control_loops/quaternion_utils.cc
index 088c699..0226e6d 100644
--- a/aos/controls/quaternion_utils.cc
+++ b/frc971/control_loops/quaternion_utils.cc
@@ -1,9 +1,9 @@
-#include "aos/controls/quaternion_utils.h"
+#include "frc971/control_loops/quaternion_utils.h"
 
 #include "Eigen/Dense"
 #include "Eigen/Geometry"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 Eigen::Matrix<double, 4, 1> ToQuaternionFromRotationVector(
@@ -136,4 +136,4 @@
 }
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
diff --git a/aos/controls/quaternion_utils.h b/frc971/control_loops/quaternion_utils.h
similarity index 97%
rename from aos/controls/quaternion_utils.h
rename to frc971/control_loops/quaternion_utils.h
index 1455821..25ffa91 100644
--- a/aos/controls/quaternion_utils.h
+++ b/frc971/control_loops/quaternion_utils.h
@@ -5,7 +5,7 @@
 #include "Eigen/Geometry"
 #include "glog/logging.h"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 
 // Function to compute the quaternion average of a bunch of quaternions. Each
@@ -66,6 +66,6 @@
     const double max_angle_cap = std::numeric_limits<double>::infinity());
 
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
 
 #endif  // AOS_CONTROLS_QUATERNION_UTILS_H_
diff --git a/aos/controls/quaternion_utils_test.cc b/frc971/control_loops/quaternion_utils_test.cc
similarity index 97%
rename from aos/controls/quaternion_utils_test.cc
rename to frc971/control_loops/quaternion_utils_test.cc
index ec410db..f472a46 100644
--- a/aos/controls/quaternion_utils_test.cc
+++ b/frc971/control_loops/quaternion_utils_test.cc
@@ -2,12 +2,12 @@
 
 #include <random>
 
-#include "aos/controls/quaternion_utils.h"
+#include "frc971/control_loops/quaternion_utils.h"
 #include "aos/testing/random_seed.h"
 #include "glog/logging.h"
 #include "gtest/gtest.h"
 
-namespace aos {
+namespace frc971 {
 namespace controls {
 namespace testing {
 
@@ -149,4 +149,4 @@
 
 }  // namespace testing
 }  // namespace controls
-}  // namespace aos
+}  // namespace frc971
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
index 1bebbe1..cb0f651 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
@@ -1,11 +1,10 @@
-#include "flatbuffers/flatbuffers.h"
-#include "gtest/gtest.h"
-
-#include "aos/controls/control_loop.h"
-#include "aos/controls/control_loop_test.h"
-#include "frc971/control_loops/capped_test_plant.h"
-#include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+
+#include "flatbuffers/flatbuffers.h"
+#include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_absolute_encoder_status_generated.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_absolute_position_generated.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_integral_plant.h"
@@ -15,6 +14,7 @@
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_subsystem_goal_generated.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_subsystem_output_generated.h"
 #include "frc971/zeroing/zeroing.h"
+#include "gtest/gtest.h"
 
 using ::frc971::control_loops::PositionSensorSimulator;
 
@@ -163,7 +163,8 @@
     typename ::aos::Sender<PositionType>::Builder position =
         subsystem_position_sender_.MakeBuilder();
 
-    auto real_position_builder = position.template MakeBuilder<RealPositionType>();
+    auto real_position_builder =
+        position.template MakeBuilder<RealPositionType>();
     flatbuffers::Offset<RealPositionType> position_offset =
         this->subsystem_sensor_sim_
             .template GetSensorValues<typename RealPositionType::Builder>(
@@ -262,7 +263,7 @@
 // to wrap it.
 template <typename QueueGroup, typename SZSDPS>
 class Subsystem
-    : public ::aos::controls::ControlLoop<
+    : public ::frc971::controls::ControlLoop<
           typename QueueGroup::Goal, typename QueueGroup::Position,
           typename QueueGroup::Status, typename QueueGroup::Output> {
  public:
@@ -272,7 +273,7 @@
   typedef typename QueueGroup::Output OutputType;
 
   Subsystem(::aos::EventLoop *event_loop, const ::std::string &name)
-      : aos::controls::ControlLoop<
+      : frc971::controls::ControlLoop<
             typename QueueGroup::Goal, typename QueueGroup::Position,
             typename QueueGroup::Status, typename QueueGroup::Output>(
             event_loop, name),
@@ -347,7 +348,7 @@
 };
 
 template <typename TSZSDPS>
-class IntakeSystemTest : public ::aos::testing::ControlLoopTest {
+class IntakeSystemTest : public ::frc971::testing::ControlLoopTest {
  protected:
   using SZSDPS = typename TSZSDPS::first_type;
   using QueueGroup = typename TSZSDPS::second_type;
@@ -360,7 +361,7 @@
   typedef typename QueueGroup::Output OutputType;
 
   IntakeSystemTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("frc971/control_loops/"
                                            "static_zeroing_single_dof_profiled_"
                                            "subsystem_test_config.json"),
diff --git a/frc971/control_loops/zeroed_joint.h b/frc971/control_loops/zeroed_joint.h
index 41269eb..449cee1 100644
--- a/frc971/control_loops/zeroed_joint.h
+++ b/frc971/control_loops/zeroed_joint.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 
 namespace frc971 {
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index 2ce45e9..b104840 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -119,7 +119,7 @@
                      frc::DigitalInput *dio1)
     : event_loop_(event_loop),
       imu_values_sender_(
-          event_loop_->MakeSender<::frc971::IMUValues>("/drivetrain")),
+          event_loop_->MakeSender<::frc971::IMUValuesBatch>("/drivetrain")),
       spi_(new frc::SPI(port)),
       dio1_(dio1) {
   // 1MHz is the maximum supported for burst reads, but we
@@ -276,7 +276,15 @@
         ConvertValue(&to_receive[24], kTemperatureLsbDegree) +
         kTemperatureZero);
 
-    if (!builder.Send(imu_builder.Finish())) {
+    flatbuffers::Offset<IMUValues> imu_offset = imu_builder.Finish();
+
+    flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<IMUValues>>>
+        readings_offset = builder.fbb()->CreateVector(&imu_offset, 1);
+
+    IMUValuesBatch::Builder imu_values_batch_builder =
+        builder.MakeBuilder<IMUValuesBatch>();
+    imu_values_batch_builder.add_readings(readings_offset);
+    if (!builder.Send(imu_values_batch_builder.Finish())) {
       AOS_LOG(WARNING, "sending queue message failed\n");
     }
 
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 04d1712..59f9aa8 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -14,6 +14,7 @@
 #include "aos/events/shm_event_loop.h"
 #include "aos/logging/logging.h"
 #include "frc971/wpilib/fpga_time_conversion.h"
+#include "frc971/wpilib/imu_batch_generated.h"
 #include "frc971/wpilib/imu_generated.h"
 #include "frc971/wpilib/spi_rx_clearer.h"
 
@@ -85,7 +86,7 @@
   bool Initialize();
 
   ::aos::EventLoop *event_loop_;
-  ::aos::Sender<::frc971::IMUValues> imu_values_sender_;
+  ::aos::Sender<::frc971::IMUValuesBatch> imu_values_sender_;
 
   // TODO(Brian): This object has no business owning these ones.
   const ::std::unique_ptr<frc::SPI> spi_;
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index 4f8bca0..10e8462 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -115,9 +115,9 @@
         "//aos/events:event_loop",
         "//aos/events:shm_event_loop",
         "//aos/logging",
-        "//frc971/input:robot_state_fbs",
         "//aos/time",
         "//aos/util:phased_loop",
+        "//frc971/input:robot_state_fbs",
         "//frc971/queues:gyro_fbs",
         "//frc971/queues:gyro_uid_fbs",
         "//frc971/zeroing:averager",
@@ -167,10 +167,10 @@
     deps = [
         "//aos:init",
         "//aos/events:event_loop",
-        "//frc971/input:robot_state_fbs",
         "//aos/scoped:scoped_fd",
         "//aos/time",
         "//aos/util:log_interval",
+        "//frc971/input:robot_state_fbs",
     ],
 )
 
@@ -204,8 +204,8 @@
     deps = [
         "//aos:init",
         "//aos/events:shm_event_loop",
-        "//frc971/input:driver_station_data",
         "//aos/network:team_number",
+        "//frc971/input:driver_station_data",
         "//frc971/input:joystick_state_fbs",
         "//third_party:wpilib",
     ],
@@ -331,6 +331,7 @@
     target_compatible_with = ["//tools/platforms/hardware:roborio"],
     deps = [
         ":fpga_time_conversion",
+        ":imu_batch_fbs",
         ":imu_fbs",
         ":spi_rx_clearer",
         "//aos:init",
diff --git a/frc971/zeroing/imu_zeroer.cc b/frc971/zeroing/imu_zeroer.cc
index 70c5a42..a9b1045 100644
--- a/frc971/zeroing/imu_zeroer.cc
+++ b/frc971/zeroing/imu_zeroer.cc
@@ -111,6 +111,10 @@
   builder.add_gyro_y_average(GyroOffset().y());
   builder.add_gyro_z_average(GyroOffset().z());
 
+  builder.add_accel_x_average(accel_average_.x());
+  builder.add_accel_y_average(accel_average_.y());
+  builder.add_accel_z_average(accel_average_.z());
+
   return builder.Finish();
 }
 
diff --git a/y2012/BUILD b/y2012/BUILD
index ea88af8..450abfa 100644
--- a/y2012/BUILD
+++ b/y2012/BUILD
@@ -9,7 +9,6 @@
     deps = [
         "//aos:init",
         "//aos/actions:action_lib",
-        "//frc971/input:joystick_input",
         "//aos/logging",
         "//aos/time",
         "//aos/util:log_interval",
@@ -17,6 +16,7 @@
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_goal_fbs",
         "//frc971/control_loops/drivetrain:spline_goal_fbs",
+        "//frc971/input:joystick_input",
         "//y2012/control_loops/accessories:accessories_fbs",
     ],
 )
@@ -40,11 +40,9 @@
     deps = [
         "//aos:init",
         "//aos:make_unique",
-        "//aos/controls:control_loop",
-        "//aos/controls:control_loop_fbs",
+        "//frc971/control_loops:control_loop",
         "//aos/events:shm_event_loop",
         "//aos/logging",
-        "//frc971/input:robot_state_fbs",
         "//aos/stl_mutex",
         "//aos/time",
         "//aos/util:log_interval",
@@ -53,6 +51,7 @@
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_output_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_position_fbs",
+        "//frc971/input:robot_state_fbs",
         "//frc971/wpilib:buffered_pcm",
         "//frc971/wpilib:dma",
         "//frc971/wpilib:dma_edge_counting",
@@ -66,6 +65,7 @@
         "//frc971/wpilib:wpilib_interface",
         "//frc971/wpilib:wpilib_robot_base",
         "//third_party:wpilib",
+        "//y2012/control_loops:control_loop_fbs",
         "//y2012/control_loops/accessories:accessories_fbs",
     ],
 )
diff --git a/y2012/control_loops/BUILD b/y2012/control_loops/BUILD
index 1cf6e97..ef4e03f 100644
--- a/y2012/control_loops/BUILD
+++ b/y2012/control_loops/BUILD
@@ -1,3 +1,5 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+
 py_library(
     name = "python_init",
     srcs = ["__init__.py"],
@@ -5,3 +7,12 @@
     visibility = ["//visibility:public"],
     deps = ["//y2012:python_init"],
 )
+
+flatbuffer_cc_library(
+    name = "control_loop_fbs",
+    srcs = [
+        "control_loops.fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//y2012:__subpackages__"],
+)
diff --git a/y2012/control_loops/accessories/BUILD b/y2012/control_loops/accessories/BUILD
index 02a15f1..ee61511 100644
--- a/y2012/control_loops/accessories/BUILD
+++ b/y2012/control_loops/accessories/BUILD
@@ -11,8 +11,8 @@
     deps = [
         ":accessories_fbs",
         "//aos:init",
-        "//aos/controls:control_loop",
-        "//aos/controls:control_loop_fbs",
+        "//frc971/control_loops:control_loop",
+        "//y2012/control_loops:control_loop_fbs",
     ],
 )
 
diff --git a/y2012/control_loops/accessories/accessories.cc b/y2012/control_loops/accessories/accessories.cc
index 5627c7b..c71146e 100644
--- a/y2012/control_loops/accessories/accessories.cc
+++ b/y2012/control_loops/accessories/accessories.cc
@@ -1,30 +1,29 @@
-#include "y2012/control_loops/accessories/accessories_generated.h"
-
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
-#include "aos/controls/control_loop.h"
-#include "aos/controls/control_loops_generated.h"
+#include "frc971/control_loops/control_loop.h"
+#include "y2012/control_loops/accessories/accessories_generated.h"
+#include "y2012/control_loops/control_loops_generated.h"
 
 namespace y2012 {
 namespace control_loops {
 namespace accessories {
 
-class AccessoriesLoop : public ::aos::controls::ControlLoop<
+class AccessoriesLoop : public ::frc971::controls::ControlLoop<
                             Message, ::aos::control_loops::Position,
                             ::aos::control_loops::Status, Message> {
  public:
   explicit AccessoriesLoop(
       ::aos::EventLoop *event_loop,
       const ::std::string &name = ".y2012.control_loops.accessories_queue")
-      : ::aos::controls::ControlLoop<Message, ::aos::control_loops::Position,
-                                     ::aos::control_loops::Status, Message>(
+      : ::frc971::controls::ControlLoop<Message, ::aos::control_loops::Position,
+                                        ::aos::control_loops::Status, Message>(
             event_loop, name) {}
 
-  void RunIteration(
-      const Message *goal,
-      const ::aos::control_loops::Position * /*position*/,
-      ::aos::Sender<Message>::Builder *output,
-      ::aos::Sender<::aos::control_loops::Status>::Builder * /*status*/) override {
+  void RunIteration(const Message *goal,
+                    const ::aos::control_loops::Position * /*position*/,
+                    ::aos::Sender<Message>::Builder *output,
+                    ::aos::Sender<::aos::control_loops::Status>::Builder
+                        * /*status*/) override {
     if (output) {
       //*output = *goal;
       Message::Builder output_builder = output->MakeBuilder<Message>();
@@ -33,8 +32,8 @@
               goal->solenoids()->data(), 3);
       output_builder.add_solenoids(solenoid_offset);
       flatbuffers::Offset<flatbuffers::Vector<double>> stick_offset =
-          output->fbb()->template CreateVector<double>(
-              goal->sticks()->data(), 2);
+          output->fbb()->template CreateVector<double>(goal->sticks()->data(),
+                                                       2);
       output_builder.add_sticks(stick_offset);
 
       output_builder.Finish();
diff --git a/aos/controls/control_loops.fbs b/y2012/control_loops/control_loops.fbs
similarity index 100%
rename from aos/controls/control_loops.fbs
rename to y2012/control_loops/control_loops.fbs
diff --git a/y2012/wpilib_interface.cc b/y2012/wpilib_interface.cc
index f611c93..959e198 100644
--- a/y2012/wpilib_interface.cc
+++ b/y2012/wpilib_interface.cc
@@ -19,7 +19,6 @@
 #include "frc971/wpilib/wpilib_robot_base.h"
 #undef ERROR
 
-#include "aos/controls/control_loops_generated.h"
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "aos/logging/logging.h"
@@ -44,6 +43,7 @@
 #include "frc971/wpilib/loop_output_handler.h"
 #include "frc971/wpilib/sensor_reader.h"
 #include "y2012/control_loops/accessories/accessories_generated.h"
+#include "y2012/control_loops/control_loops_generated.h"
 
 namespace accessories = ::y2012::control_loops::accessories;
 using namespace frc;
diff --git a/y2014/BUILD b/y2014/BUILD
index a223253..15e187f 100644
--- a/y2014/BUILD
+++ b/y2014/BUILD
@@ -106,7 +106,7 @@
         ":constants",
         "//aos:init",
         "//aos:make_unique",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
         "//aos/stl_mutex",
diff --git a/y2014/control_loops/claw/BUILD b/y2014/control_loops/claw/BUILD
index f8865a5..a79dc78 100644
--- a/y2014/control_loops/claw/BUILD
+++ b/y2014/control_loops/claw/BUILD
@@ -75,8 +75,8 @@
         ":claw_position_fbs",
         ":claw_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop",
-        "//aos/controls:polytope",
+        "//frc971/control_loops:control_loop",
+        "//frc971/control_loops:polytope",
         "//frc971/control_loops:coerce_goal",
         "//frc971/control_loops:hall_effect_tracker",
         "//frc971/control_loops:state_feedback_loop",
@@ -97,7 +97,7 @@
         ":claw_output_fbs",
         ":claw_position_fbs",
         ":claw_status_fbs",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//frc971/control_loops:state_feedback_loop",
         "//frc971/control_loops:team_number_test_environment",
diff --git a/y2014/control_loops/claw/claw.cc b/y2014/control_loops/claw/claw.cc
index 56ca6b0..4f0248c 100644
--- a/y2014/control_loops/claw/claw.cc
+++ b/y2014/control_loops/claw/claw.cc
@@ -2,9 +2,8 @@
 
 #include <algorithm>
 
-#include "aos/logging/logging.h"
 #include "aos/commonmath.h"
-
+#include "aos/logging/logging.h"
 #include "y2014/constants.h"
 #include "y2014/control_loops/claw/claw_motor_plant.h"
 
@@ -46,8 +45,8 @@
 namespace claw {
 
 using ::frc971::HallEffectTracker;
-using ::y2014::control_loops::claw::kDt;
 using ::frc971::control_loops::DoCoerceGoal;
+using ::y2014::control_loops::claw::kDt;
 
 static const double kZeroingVoltage = 4.0;
 static const double kMaxVoltage = 12.0;
@@ -57,20 +56,18 @@
     : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
       uncapped_average_voltage_(0.0),
       is_zeroing_(true),
-      U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0,
-               -1, 0,
-               0, 1,
-               0, -1).finished(),
+      U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0, -1, 0, 0, 1, 0, -1)
+                  .finished(),
               (Eigen::Matrix<double, 4, 1>() << kMaxVoltage, kMaxVoltage,
-               kMaxVoltage, kMaxVoltage).finished()),
-      U_Poly_zeroing_((Eigen::Matrix<double, 4, 2>() << 1, 0,
-               -1, 0,
-               0, 1,
-               0, -1).finished(),
-              (Eigen::Matrix<double, 4, 1>() <<
-               kZeroingVoltage, kZeroingVoltage,
-               kZeroingVoltage, kZeroingVoltage).finished()) {
-  ::aos::controls::HPolytope<0>::Init();
+               kMaxVoltage, kMaxVoltage)
+                  .finished()),
+      U_Poly_zeroing_(
+          (Eigen::Matrix<double, 4, 2>() << 1, 0, -1, 0, 0, 1, 0, -1)
+              .finished(),
+          (Eigen::Matrix<double, 4, 1>() << kZeroingVoltage, kZeroingVoltage,
+           kZeroingVoltage, kZeroingVoltage)
+              .finished()) {
+  ::frc971::controls::HPolytope<0>::Init();
 }
 
 // Caps the voltage prioritizing reducing velocity error over reducing
@@ -119,8 +116,8 @@
     const Eigen::Matrix<double, 4, 2> pos_poly_H = poly.H() * position_K;
     const Eigen::Matrix<double, 4, 1> pos_poly_k =
         poly.k() - poly.H() * velocity_K * velocity_error;
-    const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
-    const ::aos::controls::HVPolytope<2, 4, 4> hv_pos_poly(
+    const ::frc971::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
+    const ::frc971::controls::HVPolytope<2, 4, 4> hv_pos_poly(
         pos_poly_H, pos_poly_k, pos_poly.Vertices());
 
     Eigen::Matrix<double, 2, 1> adjusted_pos_error;
@@ -187,7 +184,8 @@
     {
       const auto values = constants::GetValues().claw;
       if (top_known_) {
-        if (X_hat(0, 0) + X_hat(1, 0) > values.upper_claw.upper_limit && U(1, 0) > 0) {
+        if (X_hat(0, 0) + X_hat(1, 0) > values.upper_claw.upper_limit &&
+            U(1, 0) > 0) {
           AOS_LOG(WARNING, "upper claw too high and moving up\n");
           mutable_U(1, 0) = 0;
         } else if (X_hat(0, 0) + X_hat(1, 0) < values.upper_claw.lower_limit &&
@@ -337,7 +335,6 @@
   }
 }
 
-
 void BottomZeroedStateFeedbackLoop::HandleCalibrationError(
     const constants::Values::Claws::Claw &claw_values) {
   double edge_encoder;
@@ -369,8 +366,8 @@
 }
 
 ClawMotor::ClawMotor(::aos::EventLoop *event_loop, const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       has_top_claw_goal_(false),
       top_claw_goal_(0.0),
       top_claw_(this),
@@ -692,9 +689,9 @@
     bottom_claw_.HandleCalibrationError(values.claw.lower_claw);
     top_claw_.HandleCalibrationError(values.claw.upper_claw);
   } else if (top_claw_.zeroing_state() !=
-             ZeroedStateFeedbackLoop::UNKNOWN_POSITION &&
+                 ZeroedStateFeedbackLoop::UNKNOWN_POSITION &&
              bottom_claw_.zeroing_state() !=
-             ZeroedStateFeedbackLoop::UNKNOWN_POSITION) {
+                 ZeroedStateFeedbackLoop::UNKNOWN_POSITION) {
     // Time to fine tune the zero.
     // Limit the goals here.
     if (!enabled) {
@@ -920,8 +917,8 @@
         bottom_claw_goal_ -= dx;
         top_claw_goal_ -= dx;
         Eigen::Matrix<double, 4, 1> R;
-        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_, claw_.R(2, 0),
-            claw_.R(3, 0);
+        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_,
+            claw_.R(2, 0), claw_.R(3, 0);
         claw_.mutable_U() = claw_.controller().K() * (R - claw_.X_hat());
         capped_goal_ = true;
         AOS_LOG(DEBUG,
@@ -943,8 +940,8 @@
         bottom_claw_goal_ -= dx;
         top_claw_goal_ -= dx;
         Eigen::Matrix<double, 4, 1> R;
-        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_, claw_.R(2, 0),
-            claw_.R(3, 0);
+        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_,
+            claw_.R(2, 0), claw_.R(3, 0);
         claw_.mutable_U() = claw_.controller().K() * (R - claw_.X_hat());
         capped_goal_ = true;
         AOS_LOG(DEBUG, "Moving the goal by %f to prevent windup\n", dx);
@@ -954,16 +951,16 @@
 
   if (output) {
     if (goal) {
-      //setup the intake
+      // setup the intake
       output_struct.intake_voltage =
           (goal->intake() > 12.0)
               ? 12
               : (goal->intake() < -12.0) ? -12.0 : goal->intake();
       output_struct.tusk_voltage = goal->centering();
       output_struct.tusk_voltage =
-          (goal->centering() > 12.0) ? 12 : (goal->centering() < -12.0)
-              ? -12.0
-              : goal->centering();
+          (goal->centering() > 12.0)
+              ? 12
+              : (goal->centering() < -12.0) ? -12.0 : goal->centering();
     }
     output_struct.top_claw_voltage = claw_.U(1, 0);
     output_struct.bottom_claw_voltage = claw_.U(0, 0);
diff --git a/y2014/control_loops/claw/claw.h b/y2014/control_loops/claw/claw.h
index 5bcccc1..07a5d2a 100644
--- a/y2014/control_loops/claw/claw.h
+++ b/y2014/control_loops/claw/claw.h
@@ -3,8 +3,8 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
-#include "aos/controls/polytope.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/polytope.h"
 #include "frc971/control_loops/coerce_goal.h"
 #include "frc971/control_loops/hall_effect_tracker.h"
 #include "frc971/control_loops/state_feedback_loop.h"
@@ -49,7 +49,7 @@
 
   bool top_known_ = false, bottom_known_ = false;
 
-  const ::aos::controls::HPolytope<2> U_Poly_, U_Poly_zeroing_;
+  const ::frc971::controls::HPolytope<2> U_Poly_, U_Poly_zeroing_;
 };
 
 class ClawMotor;
@@ -88,7 +88,9 @@
   double absolute_position() const { return encoder() + offset(); }
 
   const ::frc971::HallEffectTracker &front() const { return front_; }
-  const ::frc971::HallEffectTracker &calibration() const { return calibration_; }
+  const ::frc971::HallEffectTracker &calibration() const {
+    return calibration_;
+  }
   const ::frc971::HallEffectTracker &back() const { return back_; }
 
   bool any_hall_effect_changed() const {
@@ -143,8 +145,8 @@
   double last_off_encoder_;
   bool any_triggered_last_;
 
-  const ::frc971::HallEffectTracker* posedge_filter_ = nullptr;
-  const ::frc971::HallEffectTracker* negedge_filter_ = nullptr;
+  const ::frc971::HallEffectTracker *posedge_filter_ = nullptr;
+  const ::frc971::HallEffectTracker *negedge_filter_ = nullptr;
 
  private:
   // Does the edges of 1 sensor for GetPositionOfEdge.
@@ -187,7 +189,7 @@
 };
 
 class ClawMotor
-    : public aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit ClawMotor(::aos::EventLoop *event_loop,
                      const ::std::string &name = "/claw");
diff --git a/y2014/control_loops/claw/claw_lib_test.cc b/y2014/control_loops/claw/claw_lib_test.cc
index 5222ad8..eb941a1 100644
--- a/y2014/control_loops/claw/claw_lib_test.cc
+++ b/y2014/control_loops/claw/claw_lib_test.cc
@@ -3,7 +3,7 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
 #include "y2014/constants.h"
@@ -19,15 +19,15 @@
 namespace claw {
 namespace testing {
 
-using ::frc971::HallEffectStructT;
 using ::aos::monotonic_clock;
+using ::frc971::HallEffectStructT;
 namespace chrono = ::std::chrono;
 
 typedef enum {
-	TOP_CLAW = 0,
-	BOTTOM_CLAW,
+  TOP_CLAW = 0,
+  BOTTOM_CLAW,
 
-	CLAW_COUNT
+  CLAW_COUNT
 } ClawType;
 
 // Class which simulates the wrist and sends out queue messages containing the
@@ -62,7 +62,8 @@
     AOS_LOG(INFO, "Reinitializing to {top: %f, bottom: %f}\n",
             initial_top_position, initial_bottom_position);
     claw_plant_->mutable_X(0, 0) = initial_bottom_position;
-    claw_plant_->mutable_X(1, 0) = initial_top_position - initial_bottom_position;
+    claw_plant_->mutable_X(1, 0) =
+        initial_top_position - initial_bottom_position;
     claw_plant_->mutable_X(2, 0) = 0.0;
     claw_plant_->mutable_X(3, 0) = 0.0;
     claw_plant_->mutable_Y() = claw_plant_->C() * claw_plant_->X();
@@ -199,7 +200,8 @@
     UpdateHallEffect(half_claw->position + initial_position,
                      last_position.position + initial_position,
                      initial_position, half_claw->front.get(),
-                     *last_position.front.get(), claw.front, claw_name, "front");
+                     *last_position.front.get(), claw.front, claw_name,
+                     "front");
     UpdateHallEffect(half_claw->position + initial_position,
                      last_position.position + initial_position,
                      initial_position, half_claw->calibration.get(),
@@ -245,7 +247,7 @@
 
   // Simulates the claw moving for one timestep.
   void Simulate() {
-    const constants::Values& v = constants::GetValues();
+    const constants::Values &v = constants::GetValues();
     EXPECT_TRUE(claw_output_fetcher_.Fetch());
 
     Eigen::Matrix<double, 2, 1> U;
@@ -286,10 +288,10 @@
   PositionT last_position_;
 };
 
-class ClawTest : public ::aos::testing::ControlLoopTest {
+class ClawTest : public ::frc971::testing::ControlLoopTest {
  protected:
   ClawTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2014/config.json"),
             chrono::microseconds(5000)),
         test_event_loop_(MakeEventLoop("test")),
@@ -431,10 +433,9 @@
   EXPECT_NEAR(7.5, top_goal, 1e-4);
 }
 
-
 class ZeroingClawTest
     : public ClawTest,
-      public ::testing::WithParamInterface< ::std::pair<double, double>> {};
+      public ::testing::WithParamInterface<::std::pair<double, double>> {};
 
 // Tests that the wrist zeros correctly starting on the hall effect sensor.
 TEST_P(ZeroingClawTest, ParameterizedZero) {
@@ -454,29 +455,19 @@
   VerifyNearGoal();
 }
 
-INSTANTIATE_TEST_SUITE_P(ZeroingClawTest, ZeroingClawTest,
-                        ::testing::Values(::std::make_pair(0.04, 0.02),
-                                          ::std::make_pair(0.2, 0.1),
-                                          ::std::make_pair(0.3, 0.2),
-                                          ::std::make_pair(0.4, 0.3),
-                                          ::std::make_pair(0.5, 0.4),
-                                          ::std::make_pair(0.6, 0.5),
-                                          ::std::make_pair(0.7, 0.6),
-                                          ::std::make_pair(0.8, 0.7),
-                                          ::std::make_pair(0.9, 0.8),
-                                          ::std::make_pair(1.0, 0.9),
-                                          ::std::make_pair(1.1, 1.0),
-                                          ::std::make_pair(1.15, 1.05),
-                                          ::std::make_pair(1.05, 0.95),
-                                          ::std::make_pair(1.2, 1.1),
-                                          ::std::make_pair(1.3, 1.2),
-                                          ::std::make_pair(1.4, 1.3),
-                                          ::std::make_pair(1.5, 1.4),
-                                          ::std::make_pair(1.6, 1.5),
-                                          ::std::make_pair(1.7, 1.6),
-                                          ::std::make_pair(1.8, 1.7),
-                                          ::std::make_pair(2.015, 2.01)
-));
+INSTANTIATE_TEST_SUITE_P(
+    ZeroingClawTest, ZeroingClawTest,
+    ::testing::Values(::std::make_pair(0.04, 0.02), ::std::make_pair(0.2, 0.1),
+                      ::std::make_pair(0.3, 0.2), ::std::make_pair(0.4, 0.3),
+                      ::std::make_pair(0.5, 0.4), ::std::make_pair(0.6, 0.5),
+                      ::std::make_pair(0.7, 0.6), ::std::make_pair(0.8, 0.7),
+                      ::std::make_pair(0.9, 0.8), ::std::make_pair(1.0, 0.9),
+                      ::std::make_pair(1.1, 1.0), ::std::make_pair(1.15, 1.05),
+                      ::std::make_pair(1.05, 0.95), ::std::make_pair(1.2, 1.1),
+                      ::std::make_pair(1.3, 1.2), ::std::make_pair(1.4, 1.3),
+                      ::std::make_pair(1.5, 1.4), ::std::make_pair(1.6, 1.5),
+                      ::std::make_pair(1.7, 1.6), ::std::make_pair(1.8, 1.7),
+                      ::std::make_pair(2.015, 2.01)));
 
 /*
 // Tests that loosing the encoder for a second triggers a re-zero.
@@ -559,7 +550,7 @@
                   monotonic_clock::time_point start_time, double offset) {
     SetEnabled(true);
     int capped_count = 0;
-    const constants::Values& values = constants::GetValues();
+    const constants::Values &values = constants::GetValues();
     bool kicked = false;
     bool measured = false;
     while (test_event_loop_->monotonic_now() <
diff --git a/y2014/control_loops/shooter/BUILD b/y2014/control_loops/shooter/BUILD
index 9f71e95..d67050d 100644
--- a/y2014/control_loops/shooter/BUILD
+++ b/y2014/control_loops/shooter/BUILD
@@ -78,7 +78,7 @@
         ":shooter_output_fbs",
         ":shooter_position_fbs",
         ":shooter_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:state_feedback_loop",
         "//y2014:constants",
@@ -98,7 +98,7 @@
         ":shooter_output_fbs",
         ":shooter_position_fbs",
         ":shooter_status_fbs",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//frc971/control_loops:state_feedback_loop",
         "//frc971/control_loops:team_number_test_environment",
diff --git a/y2014/control_loops/shooter/shooter.cc b/y2014/control_loops/shooter/shooter.cc
index fb115c7..52f900a 100644
--- a/y2014/control_loops/shooter/shooter.cc
+++ b/y2014/control_loops/shooter/shooter.cc
@@ -3,8 +3,8 @@
 #include <stdio.h>
 
 #include <algorithm>
-#include <limits>
 #include <chrono>
+#include <limits>
 
 #include "aos/logging/logging.h"
 #include "y2014/constants.h"
@@ -17,9 +17,9 @@
 namespace chrono = ::std::chrono;
 using ::aos::monotonic_clock;
 
-using ::y2014::control_loops::shooter::kSpringConstant;
-using ::y2014::control_loops::shooter::kMaxExtension;
 using ::y2014::control_loops::shooter::kDt;
+using ::y2014::control_loops::shooter::kMaxExtension;
+using ::y2014::control_loops::shooter::kSpringConstant;
 using ::y2014::control_loops::shooter::MakeShooterLoop;
 
 void ZeroedStateFeedbackLoop::CapU() {
@@ -103,8 +103,8 @@
 
 ShooterMotor::ShooterMotor(::aos::EventLoop *event_loop,
                            const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       shooter_(MakeShooterLoop()),
       state_(STATE_INITIALIZE),
       cycles_not_moved_(0),
@@ -138,7 +138,7 @@
   }
 
   new_pos = ::std::min(::std::max(new_pos, values.shooter.lower_limit),
-                              values.shooter.upper_limit);
+                       values.shooter.upper_limit);
   return new_pos;
 }
 
@@ -162,9 +162,8 @@
     if (position->pusher_proximal()->current()) {
       --proximal_posedge_validation_cycles_left_;
       if (proximal_posedge_validation_cycles_left_ == 0) {
-        shooter_.SetCalibration(
-            position->pusher_proximal()->posedge_value(),
-            values.shooter.pusher_proximal.upper_angle);
+        shooter_.SetCalibration(position->pusher_proximal()->posedge_value(),
+                                values.shooter.pusher_proximal.upper_angle);
 
         AOS_LOG(DEBUG, "Setting calibration using proximal sensor\n");
         zeroed_ = true;
@@ -183,9 +182,8 @@
     if (position->pusher_distal()->current()) {
       --distal_posedge_validation_cycles_left_;
       if (distal_posedge_validation_cycles_left_ == 0) {
-        shooter_.SetCalibration(
-            position->pusher_distal()->posedge_value(),
-            values.shooter.pusher_distal.upper_angle);
+        shooter_.SetCalibration(position->pusher_distal()->posedge_value(),
+                                values.shooter.pusher_distal.upper_angle);
 
         AOS_LOG(DEBUG, "Setting calibration using distal sensor\n");
         zeroed_ = true;
@@ -197,13 +195,12 @@
 }
 
 // Positive is out, and positive power is out.
-void ShooterMotor::RunIteration(
-    const Goal *goal,
-    const Position *position,
-    aos::Sender<Output>::Builder *output,
-    aos::Sender<Status>::Builder *status) {
+void ShooterMotor::RunIteration(const Goal *goal, const Position *position,
+                                aos::Sender<Output>::Builder *output,
+                                aos::Sender<Status>::Builder *status) {
   OutputT output_struct;
-  const monotonic_clock::time_point monotonic_now = event_loop()->monotonic_now();
+  const monotonic_clock::time_point monotonic_now =
+      event_loop()->monotonic_now();
   if (goal && ::std::isnan(goal->shot_power())) {
     state_ = STATE_ESTOP;
     AOS_LOG(ERROR, "Estopping because got a shot power of NAN.\n");
@@ -362,7 +359,7 @@
         latch_piston_ = true;
       }
       if (output == nullptr) {
-        load_timeout_ += ::aos::controls::kLoopFrequency;
+        load_timeout_ += ::frc971::controls::kLoopFrequency;
       }
       // Go to 0, which should be the latch position, or trigger a hall effect
       // on the way.  If we don't see edges where we are supposed to, the
@@ -391,8 +388,7 @@
                               shooter_.goal_position()) < 0.001) {
           // We are at the goal, but not latched.
           state_ = STATE_LOADING_PROBLEM;
-          loading_problem_end_time_ =
-              monotonic_now + kLoadProblemEndTimeout;
+          loading_problem_end_time_ = monotonic_now + kLoadProblemEndTimeout;
         }
       }
       if (load_timeout_ < monotonic_now) {
diff --git a/y2014/control_loops/shooter/shooter.h b/y2014/control_loops/shooter/shooter.h
index 1e7d4aa..ec383ad 100644
--- a/y2014/control_loops/shooter/shooter.h
+++ b/y2014/control_loops/shooter/shooter.h
@@ -3,10 +3,9 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
-#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/time/time.h"
-
+#include "frc971/control_loops/state_feedback_loop.h"
 #include "y2014/constants.h"
 #include "y2014/control_loops/shooter/shooter_goal_generated.h"
 #include "y2014/control_loops/shooter/shooter_motor_plant.h"
@@ -21,7 +20,7 @@
 class ShooterTest_UnloadWindupPositive_Test;
 class ShooterTest_UnloadWindupNegative_Test;
 class ShooterTest_RezeroWhileUnloading_Test;
-};
+};  // namespace testing
 
 // Note: Everything in this file assumes that there is a 1 cycle delay between
 // power being requested and it showing up at the motor.  It assumes that
@@ -131,7 +130,7 @@
     ::std::chrono::milliseconds(40);
 
 class ShooterMotor
-    : public aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit ShooterMotor(::aos::EventLoop *event_loop,
                         const ::std::string &name = "/shooter");
diff --git a/y2014/control_loops/shooter/shooter_lib_test.cc b/y2014/control_loops/shooter/shooter_lib_test.cc
index 0a7f4f6..d3217a6 100644
--- a/y2014/control_loops/shooter/shooter_lib_test.cc
+++ b/y2014/control_loops/shooter/shooter_lib_test.cc
@@ -3,8 +3,8 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
 #include "aos/network/team_number.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
 #include "y2014/constants.h"
@@ -23,9 +23,9 @@
 namespace shooter {
 namespace testing {
 
+using ::frc971::control_loops::testing::kTeamNumber;
 using ::y2014::control_loops::shooter::kMaxExtension;
 using ::y2014::control_loops::shooter::MakeRawShooterPlant;
-using ::frc971::control_loops::testing::kTeamNumber;
 
 // Class which simulates the shooter and sends out queue messages containing the
 // position.
@@ -133,8 +133,7 @@
   void UpdateEffectEdge(
       ::frc971::PosedgeOnlyCountedHallEffectStructT *sensor,
       const ::frc971::PosedgeOnlyCountedHallEffectStructT &last_sensor,
-      const constants::Values::AnglePair &limits,
-      float last_position) {
+      const constants::Values::AnglePair &limits, float last_position) {
     sensor->posedge_count = last_sensor.posedge_count;
     sensor->negedge_count = last_sensor.negedge_count;
 
@@ -288,7 +287,7 @@
     last_voltage_ = shooter_output_fetcher_->voltage();
   }
 
-  private:
+ private:
   ::aos::EventLoop *event_loop_;
   ::aos::Sender<Position> shooter_position_sender_;
   ::aos::Fetcher<Output> shooter_output_fetcher_;
@@ -327,10 +326,10 @@
 
 template <typename TestType>
 class ShooterTestTemplated
-    : public ::aos::testing::ControlLoopTestTemplated<TestType> {
+    : public ::frc971::testing::ControlLoopTestTemplated<TestType> {
  protected:
   ShooterTestTemplated()
-      : ::aos::testing::ControlLoopTestTemplated<TestType>(
+      : ::frc971::testing::ControlLoopTestTemplated<TestType>(
             aos::configuration::ReadConfig("y2014/config.json"),
             // TODO(austin): I think this runs at 5 ms in real life.
             chrono::microseconds(5000)),
@@ -554,7 +553,6 @@
   EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
 }
 
-
 TEST_F(ShooterTest, Unload) {
   SetEnabled(true);
   {
@@ -727,7 +725,6 @@
   EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
 }
 
-
 // Tests that the shooter zeros correctly and goes to a position.
 TEST_F(ShooterTest, StartsOnProximal) {
   SetEnabled(true);
@@ -760,8 +757,8 @@
   bool plunger_back = ::std::get<2>(GetParam());
   double start_pos = ::std::get<3>(GetParam());
   // flag to initialize test
-	//printf("@@@@ l= %d b= %d p= %d s= %.3f\n",
-	//		latch, brake, plunger_back, start_pos);
+  // printf("@@@@ l= %d b= %d p= %d s= %.3f\n",
+  //		latch, brake, plunger_back, start_pos);
   bool initialized = false;
   Reinitialize(start_pos);
   {
diff --git a/y2014_bot3/BUILD b/y2014_bot3/BUILD
index 4617006..7daa19e 100644
--- a/y2014_bot3/BUILD
+++ b/y2014_bot3/BUILD
@@ -40,7 +40,7 @@
     deps = [
         "//aos:init",
         "//aos:make_unique",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
         "//aos/stl_mutex",
diff --git a/y2014_bot3/control_loops/rollers/BUILD b/y2014_bot3/control_loops/rollers/BUILD
index 2f9d7c4..a4ee768 100644
--- a/y2014_bot3/control_loops/rollers/BUILD
+++ b/y2014_bot3/control_loops/rollers/BUILD
@@ -52,7 +52,7 @@
         ":rollers_output_fbs",
         ":rollers_position_fbs",
         ":rollers_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
     ],
 )
diff --git a/y2014_bot3/control_loops/rollers/rollers.cc b/y2014_bot3/control_loops/rollers/rollers.cc
index d62831a..5fcb692 100644
--- a/y2014_bot3/control_loops/rollers/rollers.cc
+++ b/y2014_bot3/control_loops/rollers/rollers.cc
@@ -11,8 +11,8 @@
 namespace rollers {
 
 Rollers::Rollers(::aos::EventLoop *event_loop, const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name) {}
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name) {}
 
 void Rollers::RunIteration(const Goal *goal, const Position * /*position*/,
                            aos::Sender<Output>::Builder *output,
diff --git a/y2014_bot3/control_loops/rollers/rollers.h b/y2014_bot3/control_loops/rollers/rollers.h
index 8903cd2..3d08f59 100644
--- a/y2014_bot3/control_loops/rollers/rollers.h
+++ b/y2014_bot3/control_loops/rollers/rollers.h
@@ -1,8 +1,7 @@
 #ifndef Y2014_BOT3_CONTROL_LOOPS_ROLLERS_H_
 #define Y2014_BOT3_CONTROL_LOOPS_ROLLERS_H_
 
-#include "aos/controls/control_loop.h"
-
+#include "frc971/control_loops/control_loop.h"
 #include "y2014_bot3/control_loops/rollers/rollers_goal_generated.h"
 #include "y2014_bot3/control_loops/rollers/rollers_output_generated.h"
 #include "y2014_bot3/control_loops/rollers/rollers_position_generated.h"
@@ -13,7 +12,7 @@
 namespace rollers {
 
 class Rollers
-    : public aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   // Constructs a control loops which can take a rollers or defaults to the
   // rollers at ::2014_bot3::control_loops::rollers.
diff --git a/y2014_bot3/output/motor_writer.cc b/y2014_bot3/output/motor_writer.cc
index 5763e49..53748bc 100644
--- a/y2014_bot3/output/motor_writer.cc
+++ b/y2014_bot3/output/motor_writer.cc
@@ -2,14 +2,13 @@
 #include <string.h>
 #include <unistd.h>
 
-#include "aos/output/motor_output.h"
-#include "aos/logging/logging.h"
+#include "frc971/control_loops/output_check.q.h"
 #include "aos/init.h"
-#include "aos/util/log_interval.h"
-#include "aos/time/time.h"
+#include "aos/logging/logging.h"
 #include "aos/logging/queue_logging.h"
-#include "aos/controls/output_check.q.h"
-
+#include "aos/output/motor_output.h"
+#include "aos/time/time.h"
+#include "aos/util/log_interval.h"
 #include "bot3/control_loops/drivetrain/drivetrain.q.h"
 #include "bot3/control_loops/rollers/rollers.q.h"
 
@@ -89,7 +88,7 @@
     }
 
     {
-      auto message = ::aos::controls::output_check_sent.MakeMessage();
+      auto message = ::frc971::controls::output_check_sent.MakeMessage();
       ++output_check_;
       if (output_check_ == 0) output_check_ = 1;
       SetRawPWMOutput(10, output_check_);
diff --git a/y2016/BUILD b/y2016/BUILD
index 9fcab25..d61eb68 100644
--- a/y2016/BUILD
+++ b/y2016/BUILD
@@ -114,7 +114,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
         "//aos/stl_mutex",
diff --git a/y2016/control_loops/shooter/BUILD b/y2016/control_loops/shooter/BUILD
index a6cf134..6cae6fa 100644
--- a/y2016/control_loops/shooter/BUILD
+++ b/y2016/control_loops/shooter/BUILD
@@ -85,7 +85,7 @@
         ":shooter_plants",
         ":shooter_position_fbs",
         ":shooter_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
     ],
 )
 
@@ -102,7 +102,7 @@
         ":shooter_output_fbs",
         ":shooter_position_fbs",
         ":shooter_status_fbs",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//frc971/control_loops:state_feedback_loop",
         "//frc971/control_loops:team_number_test_environment",
diff --git a/y2016/control_loops/shooter/shooter.cc b/y2016/control_loops/shooter/shooter.cc
index 5156a61..8b719c3 100644
--- a/y2016/control_loops/shooter/shooter.cc
+++ b/y2016/control_loops/shooter/shooter.cc
@@ -56,7 +56,7 @@
   // Compute the distance moved over that time period.
   const double avg_angular_velocity =
       (history_[oldest_history_position] - history_[history_position_]) /
-      (::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency) *
+      (::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency) *
        static_cast<double>(kHistoryLength - 1));
   shooter_side_status_builder.add_avg_angular_velocity(avg_angular_velocity);
 
@@ -71,8 +71,8 @@
 }
 
 Shooter::Shooter(::aos::EventLoop *event_loop, const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       shots_(0),
       last_pre_shot_timeout_(::aos::monotonic_clock::min_time) {}
 
diff --git a/y2016/control_loops/shooter/shooter.h b/y2016/control_loops/shooter/shooter.h
index 07fee84..c29869c 100644
--- a/y2016/control_loops/shooter/shooter.h
+++ b/y2016/control_loops/shooter/shooter.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "aos/time/time.h"
 #include "frc971/control_loops/state_feedback_loop.h"
@@ -58,7 +58,7 @@
 };
 
 class Shooter
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Shooter(::aos::EventLoop *event_loop,
                    const ::std::string &name = "/shooter");
diff --git a/y2016/control_loops/shooter/shooter_lib_test.cc b/y2016/control_loops/shooter/shooter_lib_test.cc
index c20526c..6934a75 100644
--- a/y2016/control_loops/shooter/shooter_lib_test.cc
+++ b/y2016/control_loops/shooter/shooter_lib_test.cc
@@ -1,11 +1,9 @@
-#include "y2016/control_loops/shooter/shooter.h"
-
 #include <unistd.h>
 
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
 #include "y2016/control_loops/shooter/shooter.h"
@@ -44,7 +42,6 @@
   double voltage_offset_ = 0.0;
 };
 
-
 // Class which simulates the shooter and sends out queue messages with the
 // position.
 class ShooterSimulation {
@@ -116,10 +113,10 @@
   bool first_ = true;
 };
 
-class ShooterTest : public ::aos::testing::ControlLoopTest {
+class ShooterTest : public ::frc971::testing::ControlLoopTest {
  protected:
   ShooterTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2016/config.json"),
             chrono::microseconds(5000)),
         test_event_loop_(MakeEventLoop("test")),
diff --git a/y2016/control_loops/superstructure/BUILD b/y2016/control_loops/superstructure/BUILD
index cb07ebe..b4c26d9 100644
--- a/y2016/control_loops/superstructure/BUILD
+++ b/y2016/control_loops/superstructure/BUILD
@@ -114,7 +114,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/util:trapezoid_profile",
         "//frc971/control_loops:profiled_subsystem",
         "//frc971/control_loops:simple_capped_state_feedback_loop",
@@ -139,7 +139,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//aos/time",
         "//frc971/control_loops:position_sensor_sim",
diff --git a/y2016/control_loops/superstructure/superstructure.cc b/y2016/control_loops/superstructure/superstructure.cc
index 8f4d02e..3ee7730 100644
--- a/y2016/control_loops/superstructure/superstructure.cc
+++ b/y2016/control_loops/superstructure/superstructure.cc
@@ -2,14 +2,12 @@
 
 #include "aos/commonmath.h"
 #include "aos/logging/logging.h"
-
+#include "y2016/constants.h"
 #include "y2016/control_loops/superstructure/integral_arm_plant.h"
 #include "y2016/control_loops/superstructure/integral_intake_plant.h"
 #include "y2016/control_loops/superstructure/superstructure_controls.h"
 #include "y2016/queues/ball_detector_generated.h"
 
-#include "y2016/constants.h"
-
 namespace y2016 {
 namespace control_loops {
 namespace superstructure {
@@ -207,9 +205,9 @@
 
   // The wrist must go back to zero when the shoulder is moving the arm into
   // a stowed/intaking position.
-  if (shoulder_angle <
-          CollisionAvoidance::kMinShoulderAngleForHorizontalShooter &&
-      ::std::abs(wrist_angle) > kMaxWristAngleForSafeArmStowing) {
+  if (shoulder_angle<CollisionAvoidance::kMinShoulderAngleForHorizontalShooter
+                         && ::std::abs(wrist_angle)>
+          kMaxWristAngleForSafeArmStowing) {
     AOS_LOG(DEBUG, "Collided: Shoulder %f < %f and wrist |%f| > %f.\n",
             shoulder_angle,
             CollisionAvoidance::kMinShoulderAngleForHorizontalShooter,
@@ -228,8 +226,8 @@
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       ball_detector_fetcher_(
           event_loop->MakeFetcher<::y2016::sensors::BallDetector>(
               "/superstructure")),
@@ -287,11 +285,10 @@
   }
 }
 
-void Superstructure::RunIteration(
-    const Goal *unsafe_goal,
-    const Position *position,
-    aos::Sender<Output>::Builder *output,
-    aos::Sender<Status>::Builder *status) {
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+                                  const Position *position,
+                                  aos::Sender<Output>::Builder *output,
+                                  aos::Sender<Status>::Builder *status) {
   const State state_before_switch = state_;
   if (WasReset()) {
     AOS_LOG(ERROR, "WPILib reset, restarting\n");
@@ -727,9 +724,10 @@
 
       // Intake.
       if (unsafe_goal->force_intake() || !ball_detected) {
-        output_struct.voltage_top_rollers = ::std::max(
-            -kMaxIntakeTopVoltage,
-            ::std::min(unsafe_goal->voltage_top_rollers(), kMaxIntakeTopVoltage));
+        output_struct.voltage_top_rollers =
+            ::std::max(-kMaxIntakeTopVoltage,
+                       ::std::min(unsafe_goal->voltage_top_rollers(),
+                                  kMaxIntakeTopVoltage));
         output_struct.voltage_bottom_rollers =
             ::std::max(-kMaxIntakeBottomVoltage,
                        ::std::min(unsafe_goal->voltage_bottom_rollers(),
diff --git a/y2016/control_loops/superstructure/superstructure.h b/y2016/control_loops/superstructure/superstructure.h
index 2219c95..48da666 100644
--- a/y2016/control_loops/superstructure/superstructure.h
+++ b/y2016/control_loops/superstructure/superstructure.h
@@ -3,10 +3,9 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/util/trapezoid_profile.h"
 #include "frc971/control_loops/state_feedback_loop.h"
-
 #include "frc971/zeroing/zeroing.h"
 #include "y2016/control_loops/superstructure/superstructure_controls.h"
 #include "y2016/control_loops/superstructure/superstructure_goal_generated.h"
@@ -108,7 +107,7 @@
 };
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");
diff --git a/y2016/control_loops/superstructure/superstructure_controls.cc b/y2016/control_loops/superstructure/superstructure_controls.cc
index 269089b..d16c73c 100644
--- a/y2016/control_loops/superstructure/superstructure_controls.cc
+++ b/y2016/control_loops/superstructure/superstructure_controls.cc
@@ -1,11 +1,9 @@
 #include "y2016/control_loops/superstructure/superstructure_controls.h"
 
 #include "aos/logging/logging.h"
-
-#include "y2016/control_loops/superstructure/integral_intake_plant.h"
-#include "y2016/control_loops/superstructure/integral_arm_plant.h"
-
 #include "y2016/constants.h"
+#include "y2016/control_loops/superstructure/integral_arm_plant.h"
+#include "y2016/control_loops/superstructure/integral_intake_plant.h"
 
 namespace y2016 {
 namespace control_loops {
@@ -45,8 +43,8 @@
                 constants::GetValues().shoulder.zeroing),
             ::frc971::zeroing::PotAndIndexPulseZeroingEstimator(
                 constants::GetValues().wrist.zeroing)}}),
-      shoulder_profile_(::aos::controls::kLoopFrequency),
-      wrist_profile_(::aos::controls::kLoopFrequency) {
+      shoulder_profile_(::frc971::controls::kLoopFrequency),
+      wrist_profile_(::frc971::controls::kLoopFrequency) {
   Y_.setZero();
   offset_.setZero();
   AdjustProfile(0.0, 0.0, 0.0, 0.0);
diff --git a/y2016/control_loops/superstructure/superstructure_controls.h b/y2016/control_loops/superstructure/superstructure_controls.h
index d301054..a73883b 100644
--- a/y2016/control_loops/superstructure/superstructure_controls.h
+++ b/y2016/control_loops/superstructure/superstructure_controls.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/util/trapezoid_profile.h"
 #include "frc971/control_loops/profiled_subsystem.h"
 #include "frc971/control_loops/simple_capped_state_feedback_loop.h"
diff --git a/y2016/control_loops/superstructure/superstructure_lib_test.cc b/y2016/control_loops/superstructure/superstructure_lib_test.cc
index 24bc187..49ae033 100644
--- a/y2016/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2016/control_loops/superstructure/superstructure_lib_test.cc
@@ -1,25 +1,23 @@
-#include "y2016/control_loops/superstructure/superstructure.h"
-
 #include <unistd.h>
 
 #include <chrono>
 #include <memory>
 
 #include "aos/commonmath.h"
-#include "aos/controls/control_loop_test.h"
 #include "aos/time/time.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
+#include "y2016/constants.h"
 #include "y2016/control_loops/superstructure/arm_plant.h"
 #include "y2016/control_loops/superstructure/intake_plant.h"
+#include "y2016/control_loops/superstructure/superstructure.h"
 #include "y2016/control_loops/superstructure/superstructure_goal_generated.h"
 #include "y2016/control_loops/superstructure/superstructure_output_generated.h"
 #include "y2016/control_loops/superstructure/superstructure_position_generated.h"
 #include "y2016/control_loops/superstructure/superstructure_status_generated.h"
 
-#include "y2016/constants.h"
-
 using ::frc971::control_loops::PositionSensorSimulator;
 
 namespace y2016 {
@@ -350,10 +348,10 @@
   double peak_wrist_velocity_ = 1e10;
 };
 
-class SuperstructureTest : public ::aos::testing::ControlLoopTest {
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
  protected:
   SuperstructureTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2016/config.json"),
             chrono::microseconds(5000)),
         test_event_loop_(MakeEventLoop("test")),
diff --git a/y2017/BUILD b/y2017/BUILD
index 92779c9..36151dd 100644
--- a/y2017/BUILD
+++ b/y2017/BUILD
@@ -77,7 +77,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
         "//aos/stl_mutex",
diff --git a/y2017/control_loops/superstructure/BUILD b/y2017/control_loops/superstructure/BUILD
index fa835c1..a7c75ac 100644
--- a/y2017/control_loops/superstructure/BUILD
+++ b/y2017/control_loops/superstructure/BUILD
@@ -63,7 +63,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         ":vision_distance_average",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:event_loop",
         "//y2017:constants",
         "//y2017/control_loops/superstructure/column",
@@ -87,7 +87,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//aos/time",
         "//frc971/control_loops:position_sensor_sim",
diff --git a/y2017/control_loops/superstructure/column/BUILD b/y2017/control_loops/superstructure/column/BUILD
index 498579e..2d83482 100644
--- a/y2017/control_loops/superstructure/column/BUILD
+++ b/y2017/control_loops/superstructure/column/BUILD
@@ -48,7 +48,7 @@
         ":column_plants",
         ":column_zeroing",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:profiled_subsystem",
         "//y2017:constants",
         "//y2017/control_loops/superstructure:superstructure_position_fbs",
diff --git a/y2017/control_loops/superstructure/column/column.cc b/y2017/control_loops/superstructure/column/column.cc
index f1aea39..d5e2611 100644
--- a/y2017/control_loops/superstructure/column/column.cc
+++ b/y2017/control_loops/superstructure/column/column.cc
@@ -6,7 +6,6 @@
 #include <utility>
 
 #include "Eigen/Dense"
-
 #include "aos/commonmath.h"
 #include "frc971/constants.h"
 #include "frc971/control_loops/profiled_subsystem.h"
@@ -48,7 +47,7 @@
           ::std::move(loop), {{zeroing_constants}}),
       stuck_indexer_detector_(new StateFeedbackLoop<6, 2, 2>(
           column::MakeStuckIntegralColumnLoop())),
-      profile_(::aos::controls::kLoopFrequency),
+      profile_(::frc971::controls::kLoopFrequency),
       range_(range),
       default_velocity_(default_velocity),
       default_acceleration_(default_acceleration) {
@@ -128,7 +127,7 @@
 
   indexer_dt_velocity_ =
       (new_position.indexer()->encoder() - indexer_last_position_) /
-      ::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency);
+      ::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency);
   indexer_last_position_ = new_position.indexer()->encoder();
 
   stuck_indexer_detector_->Correct(Y_);
@@ -143,7 +142,7 @@
   indexer_average_angular_velocity_ =
       (indexer_history_[indexer_oldest_history_position] -
        indexer_history_[indexer_history_position_]) /
-      (::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency) *
+      (::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency) *
        static_cast<double>(kHistoryLength - 1));
 
   // Ready if average angular velocity is close to the goal.
@@ -253,7 +252,7 @@
         profile_.Update(unprofiled_goal_(2, 0), unprofiled_goal_(3, 0));
 
     constexpr double kDt =
-        ::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency);
+        ::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency);
 
     loop_->mutable_next_R(0, 0) = 0.0;
     // TODO(austin): This might not handle saturation right, but I'm not sure I
@@ -287,7 +286,7 @@
 
   // Run the KF predict step.
   stuck_indexer_detector_->UpdateObserver(loop_->U(),
-                                          ::aos::controls::kLoopFrequency);
+                                          ::frc971::controls::kLoopFrequency);
 }
 
 bool ColumnProfiledSubsystem::CheckHardLimits() {
@@ -382,7 +381,7 @@
   status_builder->add_voltage_error(X_hat(5, 0));
   status_builder->add_calculated_velocity(
       (turret_position() - turret_last_position_) /
-      ::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency));
+      ::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency));
 
   status_builder->add_estimator_state(estimator_state_offset);
 
@@ -558,8 +557,7 @@
       if (unsafe_turret_goal && unsafe_indexer_goal) {
         profiled_subsystem_.AdjustProfile(unsafe_turret_goal->profile_params());
         profiled_subsystem_.set_unprofiled_goal(
-            unsafe_indexer_goal->angular_velocity,
-            unsafe_turret_goal->angle());
+            unsafe_indexer_goal->angular_velocity, unsafe_turret_goal->angle());
 
         if (unsafe_turret_goal->track()) {
           if (vision_time_adjuster_.valid()) {
diff --git a/y2017/control_loops/superstructure/shooter/BUILD b/y2017/control_loops/superstructure/shooter/BUILD
index 49fa341..cb351c9 100644
--- a/y2017/control_loops/superstructure/shooter/BUILD
+++ b/y2017/control_loops/superstructure/shooter/BUILD
@@ -45,7 +45,7 @@
     visibility = ["//visibility:public"],
     deps = [
         ":shooter_plants",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:profiled_subsystem_fbs",
         "//y2017/control_loops/superstructure:superstructure_goal_fbs",
diff --git a/y2017/control_loops/superstructure/shooter/shooter.cc b/y2017/control_loops/superstructure/shooter/shooter.cc
index 0ea4836..8a2dcb9 100644
--- a/y2017/control_loops/superstructure/shooter/shooter.cc
+++ b/y2017/control_loops/superstructure/shooter/shooter.cc
@@ -130,7 +130,7 @@
 
   wheel_.set_position(position);
 
-  chrono::nanoseconds dt = ::aos::controls::kLoopFrequency;
+  chrono::nanoseconds dt = ::frc971::controls::kLoopFrequency;
   if (last_time_ != ::aos::monotonic_clock::min_time) {
     dt = position_time - last_time_;
   }
diff --git a/y2017/control_loops/superstructure/shooter/shooter.h b/y2017/control_loops/superstructure/shooter/shooter.h
index 19fc7dd..afb627d 100644
--- a/y2017/control_loops/superstructure/shooter/shooter.h
+++ b/y2017/control_loops/superstructure/shooter/shooter.h
@@ -4,7 +4,7 @@
 #include <array>
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/time/time.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "Eigen/Dense"
diff --git a/y2017/control_loops/superstructure/superstructure.cc b/y2017/control_loops/superstructure/superstructure.cc
index a0448fd..c707653 100644
--- a/y2017/control_loops/superstructure/superstructure.cc
+++ b/y2017/control_loops/superstructure/superstructure.cc
@@ -23,8 +23,8 @@
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       vision_status_fetcher_(
           event_loop->MakeFetcher<::y2017::vision::VisionStatus>("/vision")),
       drivetrain_status_fetcher_(
@@ -48,11 +48,10 @@
       });
 }
 
-void Superstructure::RunIteration(
-    const Goal *unsafe_goal,
-    const Position *position,
-    aos::Sender<Output>::Builder *output,
-    aos::Sender<Status>::Builder *status) {
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+                                  const Position *position,
+                                  aos::Sender<Output>::Builder *output,
+                                  aos::Sender<Status>::Builder *status) {
   OutputT output_struct;
   const ::aos::monotonic_clock::time_point monotonic_now =
       event_loop()->monotonic_now();
@@ -104,8 +103,8 @@
     if (distance_average_.Valid()) {
       if (unsafe_goal->use_vision_for_shots()) {
         ShotParams shot_params;
-        if (shot_interpolation_table_.GetInRange(
-                distance_average_.Get(), &shot_params)) {
+        if (shot_interpolation_table_.GetInRange(distance_average_.Get(),
+                                                 &shot_params)) {
           hood_goal_angle = shot_params.angle;
           shooter_goal.angular_velocity = shot_params.power;
           if (indexer_goal.angular_velocity != 0.0) {
@@ -115,10 +114,10 @@
           in_range = false;
         }
       }
-      AOS_LOG(
-          DEBUG, "VisionDistance %f, hood %f shooter %f, indexer %f * M_PI\n",
-          vision_distance, hood_goal_angle,
-          shooter_goal.angular_velocity, indexer_goal.angular_velocity / M_PI);
+      AOS_LOG(DEBUG,
+              "VisionDistance %f, hood %f shooter %f, indexer %f * M_PI\n",
+              vision_distance, hood_goal_angle, shooter_goal.angular_velocity,
+              indexer_goal.angular_velocity / M_PI);
     } else {
       AOS_LOG(DEBUG, "VisionNotValid %f\n", vision_distance);
       if (unsafe_goal->use_vision_for_shots()) {
diff --git a/y2017/control_loops/superstructure/superstructure.h b/y2017/control_loops/superstructure/superstructure.h
index a4c824e..ae52dae 100644
--- a/y2017/control_loops/superstructure/superstructure.h
+++ b/y2017/control_loops/superstructure/superstructure.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "y2017/control_loops/superstructure/column/column.h"
@@ -21,7 +21,7 @@
 namespace superstructure {
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");
diff --git a/y2017/control_loops/superstructure/superstructure_lib_test.cc b/y2017/control_loops/superstructure/superstructure_lib_test.cc
index 2722024..7690937 100644
--- a/y2017/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2017/control_loops/superstructure/superstructure_lib_test.cc
@@ -1,11 +1,9 @@
-#include "y2017/control_loops/superstructure/superstructure.h"
-
 #include <unistd.h>
 
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
@@ -14,6 +12,7 @@
 #include "y2017/control_loops/superstructure/hood/hood_plant.h"
 #include "y2017/control_loops/superstructure/intake/intake_plant.h"
 #include "y2017/control_loops/superstructure/shooter/shooter_plant.h"
+#include "y2017/control_loops/superstructure/superstructure.h"
 
 using ::frc971::control_loops::PositionSensorSimulator;
 
@@ -517,10 +516,10 @@
   double peak_hood_velocity_ = 1e10;
 };
 
-class SuperstructureTest : public ::aos::testing::ControlLoopTest {
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
  protected:
   SuperstructureTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2017/config.json"),
             chrono::microseconds(5050)),
         test_event_loop_(MakeEventLoop("test")),
@@ -566,20 +565,22 @@
     // Check that the angular velocity, average angular velocity, and estimated
     // angular velocity match when we are done for the shooter.
     EXPECT_NEAR(superstructure_goal_fetcher_->shooter()->angular_velocity(),
-                superstructure_status_fetcher_->shooter()->angular_velocity(), 0.1);
-    EXPECT_NEAR(superstructure_goal_fetcher_->shooter()->angular_velocity(),
-                superstructure_status_fetcher_->shooter()->avg_angular_velocity(),
+                superstructure_status_fetcher_->shooter()->angular_velocity(),
                 0.1);
+    EXPECT_NEAR(
+        superstructure_goal_fetcher_->shooter()->angular_velocity(),
+        superstructure_status_fetcher_->shooter()->avg_angular_velocity(), 0.1);
     EXPECT_NEAR(superstructure_goal_fetcher_->shooter()->angular_velocity(),
                 superstructure_plant_.shooter_velocity(), 0.1);
 
     // Check that the angular velocity, average angular velocity, and estimated
     // angular velocity match when we are done for the indexer.
     EXPECT_NEAR(superstructure_goal_fetcher_->indexer()->angular_velocity(),
-                superstructure_status_fetcher_->indexer()->angular_velocity(), 0.1);
-    EXPECT_NEAR(superstructure_goal_fetcher_->indexer()->angular_velocity(),
-                superstructure_status_fetcher_->indexer()->avg_angular_velocity(),
+                superstructure_status_fetcher_->indexer()->angular_velocity(),
                 0.1);
+    EXPECT_NEAR(
+        superstructure_goal_fetcher_->indexer()->angular_velocity(),
+        superstructure_status_fetcher_->indexer()->avg_angular_velocity(), 0.1);
     EXPECT_NEAR(superstructure_goal_fetcher_->indexer()->angular_velocity(),
                 superstructure_plant_.indexer_velocity(), 0.1);
   }
diff --git a/y2018/BUILD b/y2018/BUILD
index 044be19..4278a0f 100644
--- a/y2018/BUILD
+++ b/y2018/BUILD
@@ -76,7 +76,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
         "//aos/time",
diff --git a/y2018/control_loops/superstructure/BUILD b/y2018/control_loops/superstructure/BUILD
index d44807e..6ef3734 100644
--- a/y2018/control_loops/superstructure/BUILD
+++ b/y2018/control_loops/superstructure/BUILD
@@ -61,7 +61,7 @@
         ":superstructure_output_fbs",
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:event_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_output_fbs",
@@ -89,7 +89,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//aos/time",
         "//frc971/control_loops:position_sensor_sim",
diff --git a/y2018/control_loops/superstructure/intake/BUILD b/y2018/control_loops/superstructure/intake/BUILD
index c49b80b..fa4eb7e 100644
--- a/y2018/control_loops/superstructure/intake/BUILD
+++ b/y2018/control_loops/superstructure/intake/BUILD
@@ -43,7 +43,7 @@
     deps = [
         ":intake_plants",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/zeroing",
         "//y2018:constants",
diff --git a/y2018/control_loops/superstructure/intake/intake.h b/y2018/control_loops/superstructure/intake/intake.h
index e064c0e..7bc3986 100644
--- a/y2018/control_loops/superstructure/intake/intake.h
+++ b/y2018/control_loops/superstructure/intake/intake.h
@@ -4,7 +4,7 @@
 #include <math.h>
 
 #include "aos/commonmath.h"
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "frc971/zeroing/wrap.h"
 #include "frc971/zeroing/zeroing.h"
 #include "y2018/constants.h"
@@ -46,7 +46,7 @@
   double goal_angle(const double *unsafe_goal);
 
   constexpr static double kDt =
-      ::aos::time::DurationInSeconds(::aos::controls::kLoopFrequency);
+      ::aos::time::DurationInSeconds(::frc971::controls::kLoopFrequency);
 
   // Sets the offset of the controller to be the zeroing estimator offset when
   // possible otherwise zero.
diff --git a/y2018/control_loops/superstructure/superstructure.cc b/y2018/control_loops/superstructure/superstructure.cc
index f24da3b..a3e7d4f 100644
--- a/y2018/control_loops/superstructure/superstructure.cc
+++ b/y2018/control_loops/superstructure/superstructure.cc
@@ -25,8 +25,8 @@
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       status_light_sender_(
           event_loop->MakeSender<::y2018::StatusLight>("/superstructure")),
       vision_status_fetcher_(
@@ -131,7 +131,6 @@
           output != nullptr ? &release_arm_brake_output : nullptr,
           output != nullptr ? &claw_grabbed_output : nullptr, status->fbb());
 
-
   bool hook_release_output = false;
   bool forks_release_output = false;
   double voltage_winch_output = 0.0;
diff --git a/y2018/control_loops/superstructure/superstructure.h b/y2018/control_loops/superstructure/superstructure.h
index 78851df..63adbb2 100644
--- a/y2018/control_loops/superstructure/superstructure.h
+++ b/y2018/control_loops/superstructure/superstructure.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "aos/time/time.h"
 #include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
@@ -22,7 +22,7 @@
 namespace superstructure {
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");
diff --git a/y2018/control_loops/superstructure/superstructure_lib_test.cc b/y2018/control_loops/superstructure/superstructure_lib_test.cc
index a087356..9d2c10e 100644
--- a/y2018/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2018/control_loops/superstructure/superstructure_lib_test.cc
@@ -1,11 +1,9 @@
-#include "y2018/control_loops/superstructure/superstructure.h"
-
 #include <unistd.h>
 
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
@@ -13,6 +11,7 @@
 #include "y2018/control_loops/superstructure/arm/dynamics.h"
 #include "y2018/control_loops/superstructure/arm/generated_graph.h"
 #include "y2018/control_loops/superstructure/intake/intake_plant.h"
+#include "y2018/control_loops/superstructure/superstructure.h"
 #include "y2018/status_light_generated.h"
 #include "y2018/vision/vision_generated.h"
 
@@ -64,9 +63,8 @@
     plant_.mutable_X(0) = start_pos;
     plant_.mutable_X(2) = start_pos;
 
-    pot_encoder_.Initialize(
-        start_pos, kNoiseScalar, 0.0,
-        zeroing_constants_.measured_absolute_position);
+    pot_encoder_.Initialize(start_pos, kNoiseScalar, 0.0,
+                            zeroing_constants_.measured_absolute_position);
   }
 
   flatbuffers::Offset<IntakeElasticSensors> GetSensorValues(
@@ -106,10 +104,8 @@
     const double position_intake = plant_.Y(1);
 
     pot_encoder_.MoveTo(position_intake);
-    EXPECT_GE(position_intake,
-              constants::Values::kIntakeRange().lower_hard);
-    EXPECT_LE(position_intake,
-              constants::Values::kIntakeRange().upper_hard);
+    EXPECT_GE(position_intake, constants::Values::kIntakeRange().lower_hard);
+    EXPECT_LE(position_intake, constants::Values::kIntakeRange().upper_hard);
   }
 
  private:
@@ -312,10 +308,10 @@
   bool first_ = true;
 };
 
-class SuperstructureTest : public ::aos::testing::ControlLoopTest {
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
  protected:
   SuperstructureTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2018/config.json"),
             ::std::chrono::microseconds(5050)),
         test_event_loop_(MakeEventLoop("test")),
@@ -405,7 +401,8 @@
     intake_goal_builder.add_left_intake_angle(0.1);
     intake_goal_builder.add_right_intake_angle(0.2);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -435,7 +432,8 @@
     intake_goal_builder.add_left_intake_angle(0.1);
     intake_goal_builder.add_right_intake_angle(0.2);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -463,7 +461,8 @@
     intake_goal_builder.add_left_intake_angle(5.0 * M_PI);
     intake_goal_builder.add_right_intake_angle(5.0 * M_PI);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -501,7 +500,8 @@
     intake_goal_builder.add_left_intake_angle(-5.0 * M_PI);
     intake_goal_builder.add_right_intake_angle(-5.0 * M_PI);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -544,7 +544,8 @@
     intake_goal_builder.add_right_intake_angle(
         constants::Values::kIntakeRange().lower);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -589,7 +590,8 @@
     intake_goal_builder.add_right_intake_angle(
         constants::Values::kIntakeRange().upper);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -617,7 +619,8 @@
     intake_goal_builder.add_right_intake_angle(
         constants::Values::kIntakeRange().upper - 0.1);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -664,7 +667,8 @@
     intake_goal_builder.add_left_intake_angle(-0.8);
     intake_goal_builder.add_right_intake_angle(-0.8);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -687,7 +691,8 @@
     intake_goal_builder.add_left_intake_angle(0.0);
     intake_goal_builder.add_right_intake_angle(0.0);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -708,7 +713,8 @@
     intake_goal_builder.add_left_intake_angle(0.0);
     intake_goal_builder.add_right_intake_angle(0.0);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -734,7 +740,8 @@
     intake_goal_builder.add_left_intake_angle(0.0);
     intake_goal_builder.add_right_intake_angle(0.0);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -755,7 +762,8 @@
     intake_goal_builder.add_left_intake_angle(0.0);
     intake_goal_builder.add_right_intake_angle(0.0);
 
-    flatbuffers::Offset<IntakeGoal> intake_offset = intake_goal_builder.Finish();
+    flatbuffers::Offset<IntakeGoal> intake_offset =
+        intake_goal_builder.Finish();
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
     goal_builder.add_intake(intake_offset);
@@ -769,7 +777,6 @@
   VerifyNearGoal();
 }
 
-
 // TODO(austin): Test multiple path segments.
 // TODO(austin): Disable in the middle and test recovery.
 
diff --git a/y2019/BUILD b/y2019/BUILD
index 64d825e..ec777e3 100644
--- a/y2019/BUILD
+++ b/y2019/BUILD
@@ -65,7 +65,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:shm_event_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
diff --git a/y2019/constants.cc b/y2019/constants.cc
index b14ac3e..0a56ca5 100644
--- a/y2019/constants.cc
+++ b/y2019/constants.cc
@@ -181,7 +181,8 @@
       intake->zeroing_constants.measured_absolute_position = 1.273143;
 
       wrist_params->zeroing_constants.measured_absolute_position = 0.155868;
-      wrist->potentiometer_offset = -4.257454 - 0.058039 + 0.270233 - 0.661464;
+      wrist->potentiometer_offset =
+          -4.257454 - 0.058039 + 0.270233 - 0.661464 + 0.872911951453577;
 
       stilts_params->zeroing_constants.measured_absolute_position = 0.066843;
       stilts->potentiometer_offset = -0.015760 + 0.011604 - 0.061213 + 0.006690;
diff --git a/y2019/control_loops/drivetrain/BUILD b/y2019/control_loops/drivetrain/BUILD
index 9a0e879..fd5386b 100644
--- a/y2019/control_loops/drivetrain/BUILD
+++ b/y2019/control_loops/drivetrain/BUILD
@@ -226,7 +226,7 @@
         ":drivetrain_base",
         ":event_loop_localizer",
         ":localizer",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/events:shm_event_loop",
         "//aos/network:team_number",
         "//frc971/control_loops:team_number_test_environment",
diff --git a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
index 46b9b8b..18ce95a 100644
--- a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
+++ b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
@@ -1,12 +1,11 @@
 #include <queue>
 
-#include "gtest/gtest.h"
-
-#include "aos/controls/control_loop_test.h"
 #include "aos/network/team_number.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/drivetrain/drivetrain.h"
 #include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
 #include "frc971/control_loops/team_number_test_environment.h"
+#include "gtest/gtest.h"
 #include "y2019/control_loops/drivetrain/camera_generated.h"
 #include "y2019/control_loops/drivetrain/drivetrain_base.h"
 #include "y2019/control_loops/drivetrain/event_loop_localizer.h"
@@ -32,17 +31,17 @@
 };  // namespace
 
 namespace chrono = ::std::chrono;
-using ::frc971::control_loops::drivetrain::testing::DrivetrainSimulation;
-using ::frc971::control_loops::drivetrain::DrivetrainLoop;
-using ::frc971::control_loops::drivetrain::testing::GetTestDrivetrainConfig;
 using ::aos::monotonic_clock;
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+using ::frc971::control_loops::drivetrain::testing::DrivetrainSimulation;
+using ::frc971::control_loops::drivetrain::testing::GetTestDrivetrainConfig;
 
-class LocalizedDrivetrainTest : public ::aos::testing::ControlLoopTest {
+class LocalizedDrivetrainTest : public ::frc971::testing::ControlLoopTest {
  protected:
   // We must use the 2019 drivetrain config so that we don't have to deal
   // with shifting:
   LocalizedDrivetrainTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig(
                 "y2019/control_loops/drivetrain/simulation_config.json"),
             GetTest2019DrivetrainConfig().dt),
diff --git a/y2019/control_loops/superstructure/BUILD b/y2019/control_loops/superstructure/BUILD
index d89b1f3..29e04fe 100644
--- a/y2019/control_loops/superstructure/BUILD
+++ b/y2019/control_loops/superstructure/BUILD
@@ -66,7 +66,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         ":vacuum",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:event_loop",
         "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
         "//y2019:constants",
@@ -90,7 +90,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/testing:googletest",
         "//aos/time",
         "//frc971/control_loops:capped_test_plant",
@@ -127,7 +127,7 @@
     deps = [
         ":superstructure_goal_fbs",
         ":superstructure_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971:constants",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:profiled_subsystem_fbs",
@@ -146,7 +146,7 @@
     deps = [
         ":superstructure_goal_fbs",
         ":superstructure_output_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:profiled_subsystem_fbs",
     ],
diff --git a/y2019/control_loops/superstructure/superstructure.cc b/y2019/control_loops/superstructure/superstructure.cc
index 4246397..9e7a5fe 100644
--- a/y2019/control_loops/superstructure/superstructure.cc
+++ b/y2019/control_loops/superstructure/superstructure.cc
@@ -10,13 +10,13 @@
 namespace control_loops {
 namespace superstructure {
 
-using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
 using frc971::control_loops::AbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       status_light_sender_(
           event_loop->MakeSender<::y2019::StatusLight>("/superstructure")),
       drivetrain_status_fetcher_(
diff --git a/y2019/control_loops/superstructure/superstructure.h b/y2019/control_loops/superstructure/superstructure.h
index f4a23d9..f86d64c 100644
--- a/y2019/control_loops/superstructure/superstructure.h
+++ b/y2019/control_loops/superstructure/superstructure.h
@@ -1,7 +1,7 @@
 #ifndef Y2019_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 #define Y2019_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
@@ -19,7 +19,7 @@
 namespace superstructure {
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");
diff --git a/y2019/control_loops/superstructure/superstructure_lib_test.cc b/y2019/control_loops/superstructure/superstructure_lib_test.cc
index 58bac76..cabb4e2 100644
--- a/y2019/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2019/control_loops/superstructure/superstructure_lib_test.cc
@@ -3,8 +3,8 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
 #include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
@@ -399,10 +399,10 @@
   CollisionAvoidance collision_avoidance_;
 };
 
-class SuperstructureTest : public ::aos::testing::ControlLoopTest {
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
  protected:
   SuperstructureTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2019/config.json"),
             chrono::microseconds(5050)),
         test_event_loop_(MakeEventLoop("test")),
@@ -570,7 +570,6 @@
   {
     auto builder = superstructure_goal_sender_.MakeBuilder();
 
-
     flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
         elevator_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
             *builder.fbb(), constants::Values::kElevatorRange().upper);
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index 00ec2ab..d644ee7 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -598,8 +598,7 @@
             event_loop->MakeFetcher<::y2019::StatusLight>("/superstructure")),
         pneumatics_to_log_sender_(
             event_loop->MakeSender<::frc971::wpilib::PneumaticsToLog>("/aos")) {
-    ::aos::SetCurrentThreadName("Solenoids");
-    ::aos::SetCurrentThreadRealtimePriority(27);
+    event_loop_->SetRuntimeRealtimePriority(27);
 
     event_loop_->AddPhasedLoop([this](int iterations) { Loop(iterations); },
                                ::std::chrono::milliseconds(20),
diff --git a/y2020/BUILD b/y2020/BUILD
index da7d68c..6f21242 100644
--- a/y2020/BUILD
+++ b/y2020/BUILD
@@ -88,7 +88,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:shm_event_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
diff --git a/y2020/control_loops/drivetrain/BUILD b/y2020/control_loops/drivetrain/BUILD
index 38e00da..4fd61f6 100644
--- a/y2020/control_loops/drivetrain/BUILD
+++ b/y2020/control_loops/drivetrain/BUILD
@@ -140,7 +140,7 @@
     deps = [
         ":drivetrain_base",
         ":localizer",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/events:simulated_event_loop",
         "//aos/events/logging:log_writer",
         "//aos/network:team_number",
diff --git a/y2020/control_loops/drivetrain/localizer_test.cc b/y2020/control_loops/drivetrain/localizer_test.cc
index ab3b075..79ff5e4 100644
--- a/y2020/control_loops/drivetrain/localizer_test.cc
+++ b/y2020/control_loops/drivetrain/localizer_test.cc
@@ -1,17 +1,17 @@
+#include "y2020/control_loops/drivetrain/localizer.h"
+
 #include <queue>
 
-#include "gtest/gtest.h"
-
-#include "aos/controls/control_loop_test.h"
 #include "aos/events/logging/log_writer.h"
 #include "aos/network/message_bridge_server_generated.h"
 #include "aos/network/team_number.h"
 #include "aos/network/testing_time_converter.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/drivetrain/drivetrain.h"
 #include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
 #include "frc971/control_loops/team_number_test_environment.h"
+#include "gtest/gtest.h"
 #include "y2020/control_loops/drivetrain/drivetrain_base.h"
-#include "y2020/control_loops/drivetrain/localizer.h"
 #include "y2020/control_loops/superstructure/superstructure_status_generated.h"
 
 DEFINE_string(output_file, "",
@@ -95,12 +95,12 @@
 using frc971::control_loops::drivetrain::DrivetrainLoop;
 using frc971::control_loops::drivetrain::testing::DrivetrainSimulation;
 
-class LocalizedDrivetrainTest : public aos::testing::ControlLoopTest {
+class LocalizedDrivetrainTest : public frc971::testing::ControlLoopTest {
  protected:
   // We must use the 2020 drivetrain config so that we don't have to deal
   // with shifting:
   LocalizedDrivetrainTest()
-      : aos::testing::ControlLoopTest(
+      : frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig(
                 "y2020/control_loops/drivetrain/simulation_config.json"),
             GetTest2020DrivetrainConfig().dt),
diff --git a/y2020/control_loops/superstructure/BUILD b/y2020/control_loops/superstructure/BUILD
index fbf6a57..1b24fc4 100644
--- a/y2020/control_loops/superstructure/BUILD
+++ b/y2020/control_loops/superstructure/BUILD
@@ -66,7 +66,7 @@
         ":superstructure_output_fbs",
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:event_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
@@ -105,7 +105,7 @@
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
         "//aos:math",
-        "//aos/controls:control_loop_test",
+        "//frc971/control_loops:control_loop_test",
         "//aos/events/logging:log_writer",
         "//aos/testing:googletest",
         "//aos/time",
@@ -131,7 +131,7 @@
     deps = [
         ":superstructure_goal_fbs",
         ":superstructure_output_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:profiled_subsystem_fbs",
     ],
diff --git a/y2020/control_loops/superstructure/shooter/BUILD b/y2020/control_loops/superstructure/shooter/BUILD
index 0b65037..0694319 100644
--- a/y2020/control_loops/superstructure/shooter/BUILD
+++ b/y2020/control_loops/superstructure/shooter/BUILD
@@ -19,7 +19,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":flywheel_controller",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:profiled_subsystem",
         "//y2020/control_loops/superstructure:superstructure_goal_fbs",
         "//y2020/control_loops/superstructure:superstructure_output_fbs",
@@ -38,7 +38,7 @@
     ],
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//frc971/control_loops:profiled_subsystem",
         "//y2020/control_loops/superstructure:superstructure_goal_fbs",
         "//y2020/control_loops/superstructure:superstructure_status_fbs",
diff --git a/y2020/control_loops/superstructure/shooter/flywheel_controller.h b/y2020/control_loops/superstructure/shooter/flywheel_controller.h
index 4eafe47..df881c5 100644
--- a/y2020/control_loops/superstructure/shooter/flywheel_controller.h
+++ b/y2020/control_loops/superstructure/shooter/flywheel_controller.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/time/time.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "y2020/control_loops/superstructure/accelerator/integral_accelerator_plant.h"
diff --git a/y2020/control_loops/superstructure/shooter/shooter.h b/y2020/control_loops/superstructure/shooter/shooter.h
index 1a46949..539ecc9 100644
--- a/y2020/control_loops/superstructure/shooter/shooter.h
+++ b/y2020/control_loops/superstructure/shooter/shooter.h
@@ -1,7 +1,7 @@
 #ifndef Y2020_CONTROL_LOOPS_SHOOTER_SHOOTER_H_
 #define Y2020_CONTROL_LOOPS_SHOOTER_SHOOTER_H_
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "y2020/control_loops/superstructure/shooter/flywheel_controller.h"
 #include "y2020/control_loops/superstructure/superstructure_goal_generated.h"
diff --git a/y2020/control_loops/superstructure/superstructure.cc b/y2020/control_loops/superstructure/superstructure.cc
index 9a48095..ce816a0 100644
--- a/y2020/control_loops/superstructure/superstructure.cc
+++ b/y2020/control_loops/superstructure/superstructure.cc
@@ -12,8 +12,8 @@
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name),
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
       hood_(constants::GetValues().hood),
       intake_joint_(constants::GetValues().intake),
       turret_(constants::GetValues().turret.subsystem_params),
diff --git a/y2020/control_loops/superstructure/superstructure.h b/y2020/control_loops/superstructure/superstructure.h
index 4777aef..c03f7a7 100644
--- a/y2020/control_loops/superstructure/superstructure.h
+++ b/y2020/control_loops/superstructure/superstructure.h
@@ -1,7 +1,7 @@
 #ifndef y2020_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 #define y2020_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 #include "frc971/input/joystick_state_generated.h"
@@ -19,7 +19,7 @@
 namespace superstructure {
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");
diff --git a/y2020/control_loops/superstructure/superstructure_lib_test.cc b/y2020/control_loops/superstructure/superstructure_lib_test.cc
index f4704f5..22dd40e 100644
--- a/y2020/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2020/control_loops/superstructure/superstructure_lib_test.cc
@@ -3,9 +3,9 @@
 #include <chrono>
 #include <memory>
 
-#include "aos/controls/control_loop_test.h"
 #include "aos/events/logging/log_writer.h"
 #include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
@@ -412,10 +412,10 @@
   float climber_voltage_ = 0.0f;
 };
 
-class SuperstructureTest : public ::aos::testing::ControlLoopTest {
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
  protected:
   SuperstructureTest()
-      : ::aos::testing::ControlLoopTest(
+      : ::frc971::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2020/config.json"),
             chrono::microseconds(5050)),
         roborio_(aos::configuration::GetNode(configuration(), "roborio")),
@@ -978,21 +978,19 @@
                   superstructure_status_fetcher_->aimer()->turret_velocity());
 }
 
-
-
 // Test a manual goal
 TEST_P(SuperstructureAllianceTest, ShooterInterpolationManualGoal) {
   SetEnabled(true);
   WaitUntilZeroed();
 
   {
-     auto builder = superstructure_goal_sender_.MakeBuilder();
+    auto builder = superstructure_goal_sender_.MakeBuilder();
 
     auto shooter_goal = CreateShooterGoal(*builder.fbb(), 400.0, 500.0);
 
     flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
-      hood_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
-          *builder.fbb(), constants::Values::kHoodRange().lower);
+        hood_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+            *builder.fbb(), constants::Values::kHoodRange().lower);
 
     Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
 
@@ -1022,7 +1020,6 @@
               constants::Values::kHoodRange().lower, 0.001);
 }
 
-
 // Test an out of range value with auto tracking
 TEST_P(SuperstructureAllianceTest, ShooterInterpolationOutOfRange) {
   SetEnabled(true);
@@ -1086,11 +1083,8 @@
                    0.0);
   EXPECT_NEAR(superstructure_status_fetcher_->hood()->position(),
               constants::Values::kHoodRange().upper, 0.001);
-
 }
 
-
-
 TEST_P(SuperstructureAllianceTest, ShooterInterpolationInRange) {
   SetEnabled(true);
   const frc971::control_loops::Pose target = turret::OuterPortPose(GetParam());
@@ -1160,9 +1154,9 @@
 }
 
 INSTANTIATE_TEST_SUITE_P(ShootAnyAlliance, SuperstructureAllianceTest,
-                        ::testing::Values(aos::Alliance::kRed,
-                                          aos::Alliance::kBlue,
-                                          aos::Alliance::kInvalid));
+                         ::testing::Values(aos::Alliance::kRed,
+                                           aos::Alliance::kBlue,
+                                           aos::Alliance::kInvalid));
 
 }  // namespace testing
 }  // namespace superstructure
diff --git a/y2020/vision/rootfs/modify_rootfs.sh b/y2020/vision/rootfs/modify_rootfs.sh
index f08e635..ae1e493 100755
--- a/y2020/vision/rootfs/modify_rootfs.sh
+++ b/y2020/vision/rootfs/modify_rootfs.sh
@@ -44,7 +44,7 @@
 else
   OFFSET="$(/sbin/fdisk -lu "${IMAGE}" | grep "${IMAGE}2" | awk '{print 512*$2}')"
 
-  if [[ "$(stat -c %s "${IMAGE}")" < 3000000000 ]]; then
+  if [[ "$(stat -c %s "${IMAGE}")" < 2000000000 ]]; then
     echo "Growing image"
     dd if=/dev/zero bs=1G count=1 >> "${IMAGE}"
     START="$(/sbin/fdisk -lu "${IMAGE}" | grep "${IMAGE}2" | awk '{print $2}')"
diff --git a/y2020/vision/rootfs/target_configure.sh b/y2020/vision/rootfs/target_configure.sh
index 11b8cc8..e36a940 100755
--- a/y2020/vision/rootfs/target_configure.sh
+++ b/y2020/vision/rootfs/target_configure.sh
@@ -38,23 +38,9 @@
   libopencv-videostab3.2 \
   libopencv-viz3.2 \
   python3-opencv \
-  python3-matplotlib \
-  gstreamer1.0-plugins-bad \
-  gstreamer1.0-plugins-base \
-  gstreamer1.0-plugins-good \
-  gstreamer1.0-plugins-ugly \
-  gstreamer1.0-x \
-  gstreamer1.0-nice \
-  gstreamer1.0-gl \
-  libgstreamer-plugins-bad1.0-0 \
-  libgstreamer-plugins-base1.0-0 \
-  libgstreamer1.0-0 \
-  libgstreamer-gl1.0-0 \
   libnice10 \
   libnice-dev
 
-python3 -m pip install glog
-
 echo 'GOVERNOR="performance"' > /etc/default/cpufrequtils
 
 # Add a .bashrc and friends for root.
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2020-03-21_21-47-32.962241755.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2020-03-21_21-47-32.962241755.json
deleted file mode 100755
index 62d20f4..0000000
--- a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2020-03-21_21-47-32.962241755.json
+++ /dev/null
@@ -1,23 +0,0 @@
-{
- "node_name": "pi1",
- "team_number": 7971,
- "intrinsics": [
-  387.439758,
-  0.0,
-  358.201599,
-  0.0,
-  387.034973,
-  232.376465,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  0.140882,
-  -0.237723,
-  -0.000273,
-  0.000602,
-  0.084725
- ],
- "calibration_timestamp": 1584852452962241755
-}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2021-06-12_15-35-39.636386620.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2021-06-12_15-35-39.636386620.json
new file mode 100755
index 0000000..52f6bc0
--- /dev/null
+++ b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-1_2021-06-12_15-35-39.636386620.json
@@ -0,0 +1,23 @@
+{
+ "node_name": "pi1",
+ "team_number": 7971,
+ "intrinsics": [
+  388.369812,
+  0.0,
+  292.325653,
+  0.0,
+  388.513733,
+  224.371063,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.126935,
+  -0.218447,
+  -0.000152,
+  0.001158,
+  0.06266
+ ],
+ "calibration_timestamp": 1623537339636386620
+}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2020-03-21_21-34-48.682329573.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2020-03-21_21-34-48.682329573.json
deleted file mode 100755
index 67cc05f..0000000
--- a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2020-03-21_21-34-48.682329573.json
+++ /dev/null
@@ -1,23 +0,0 @@
-{
- "node_name": "pi2",
- "team_number": 7971,
- "intrinsics": [
-  390.917023,
-  0.0,
-  338.912598,
-  0.0,
-  390.893799,
-  240.735367,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  0.133992,
-  -0.22539,
-  -0.000965,
-  -0.000223,
-  0.067738
- ],
- "calibration_timestamp": 1584851688682329573
-}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2021-06-12_15-30-20.325393444.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2021-06-12_15-30-20.325393444.json
new file mode 100755
index 0000000..c502e35
--- /dev/null
+++ b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-2_2021-06-12_15-30-20.325393444.json
@@ -0,0 +1,23 @@
+{
+ "node_name": "pi2",
+ "team_number": 7971,
+ "intrinsics": [
+  388.7565,
+  0.0,
+  285.024506,
+  0.0,
+  388.915039,
+  222.227539,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.128415,
+  -0.212528,
+  0.001165,
+  0.000579,
+  0.054853
+ ],
+ "calibration_timestamp": 1623537020325393444
+}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2020-03-21_21-39-10.172513400.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2020-03-21_21-39-10.172513400.json
deleted file mode 100755
index 081ad95..0000000
--- a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2020-03-21_21-39-10.172513400.json
+++ /dev/null
@@ -1,23 +0,0 @@
-{
- "node_name": "pi3",
- "team_number": 7971,
- "intrinsics": [
-  389.0737,
-  0.0,
-  283.094513,
-  0.0,
-  389.047638,
-  227.70932,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  0.13731,
-  -0.222632,
-  0.000651,
-  0.000001,
-  0.059589
- ],
- "calibration_timestamp": 1584851950172513400
-}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2021-06-12_15-33-31.977365877.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2021-06-12_15-33-31.977365877.json
new file mode 100755
index 0000000..52069c3
--- /dev/null
+++ b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-3_2021-06-12_15-33-31.977365877.json
@@ -0,0 +1,23 @@
+{
+ "node_name": "pi3",
+ "team_number": 7971,
+ "intrinsics": [
+  389.35611,
+  0.0,
+  339.345673,
+  0.0,
+  389.516235,
+  240.247787,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.122511,
+  -0.209383,
+  -0.001212,
+  0.000041,
+  0.05674
+ ],
+ "calibration_timestamp": 1623537211977365877
+}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2020-03-21_21-44-00.488542608.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2020-03-21_21-44-00.488542608.json
deleted file mode 100755
index c3b30da..0000000
--- a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2020-03-21_21-44-00.488542608.json
+++ /dev/null
@@ -1,23 +0,0 @@
-{
- "node_name": "pi4",
- "team_number": 7971,
- "intrinsics": [
-  390.216858,
-  0.0,
-  291.966309,
-  0.0,
-  390.171906,
-  223.897293,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  0.137507,
-  -0.221239,
-  -0.000349,
-  0.000203,
-  0.057804
- ],
- "calibration_timestamp": 1584852240488542608
-}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2021-06-12_15-37-25.706564865.json b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2021-06-12_15-37-25.706564865.json
new file mode 100755
index 0000000..3cc765f
--- /dev/null
+++ b/y2020/vision/tools/python_code/calib_files/calibration_pi-7971-4_2021-06-12_15-37-25.706564865.json
@@ -0,0 +1,23 @@
+{
+ "node_name": "pi4",
+ "team_number": 7971,
+ "intrinsics": [
+  390.301514,
+  0.0,
+  356.104095,
+  0.0,
+  389.884491,
+  231.157303,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.128595,
+  -0.229324,
+  -0.001145,
+  0.001602,
+  0.079774
+ ],
+ "calibration_timestamp": 1623537445706564865
+}
\ No newline at end of file
diff --git a/y2021_bot3/BUILD b/y2021_bot3/BUILD
index 9429be4..a8f6c01 100644
--- a/y2021_bot3/BUILD
+++ b/y2021_bot3/BUILD
@@ -48,7 +48,7 @@
         "//aos:init",
         "//aos:make_unique",
         "//aos:math",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:shm_event_loop",
         "//aos/logging",
         "//frc971/input:robot_state_fbs",
diff --git a/y2021_bot3/control_loops/superstructure/BUILD b/y2021_bot3/control_loops/superstructure/BUILD
index 6c716a5..24cc73f 100644
--- a/y2021_bot3/control_loops/superstructure/BUILD
+++ b/y2021_bot3/control_loops/superstructure/BUILD
@@ -59,7 +59,7 @@
         ":superstructure_output_fbs",
         ":superstructure_position_fbs",
         ":superstructure_status_fbs",
-        "//aos/controls:control_loop",
+        "//frc971/control_loops:control_loop",
         "//aos/events:event_loop",
         "//y2021_bot3:constants",
     ],
diff --git a/y2021_bot3/control_loops/superstructure/superstructure.cc b/y2021_bot3/control_loops/superstructure/superstructure.cc
index ceb479f..aaf3def 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure.cc
+++ b/y2021_bot3/control_loops/superstructure/superstructure.cc
@@ -11,8 +11,8 @@
 
 Superstructure::Superstructure(::aos::EventLoop *event_loop,
                                const ::std::string &name)
-    : aos::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
-                                                                 name) {
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name) {
   event_loop->SetRuntimeRealtimePriority(30);
 }
 
diff --git a/y2021_bot3/control_loops/superstructure/superstructure.h b/y2021_bot3/control_loops/superstructure/superstructure.h
index 3c25fd0..da4da62 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure.h
+++ b/y2021_bot3/control_loops/superstructure/superstructure.h
@@ -1,7 +1,7 @@
 #ifndef Y2021_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 #define Y2021_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
 
-#include "aos/controls/control_loop.h"
+#include "frc971/control_loops/control_loop.h"
 #include "aos/events/event_loop.h"
 #include "y2021_bot3/constants.h"
 #include "y2021_bot3/control_loops/superstructure/superstructure_goal_generated.h"
@@ -14,7 +14,7 @@
 namespace superstructure {
 
 class Superstructure
-    : public ::aos::controls::ControlLoop<Goal, Position, Status, Output> {
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
  public:
   explicit Superstructure(::aos::EventLoop *event_loop,
                           const ::std::string &name = "/superstructure");