Merge "scouting: Make /sha256/ requests stricter"
diff --git a/aos/actions/action_test.cc b/aos/actions/action_test.cc
index e7a3c53..2638cdc 100644
--- a/aos/actions/action_test.cc
+++ b/aos/actions/action_test.cc
@@ -4,14 +4,13 @@
 #include <memory>
 #include <thread>
 
-#include "gtest/gtest.h"
-
 #include "aos/actions/actions.h"
 #include "aos/actions/actions_generated.h"
 #include "aos/actions/actor.h"
 #include "aos/actions/test_action_generated.h"
 #include "aos/events/simulated_event_loop.h"
 #include "aos/testing/path.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace common {
diff --git a/aos/actions/actions.cc b/aos/actions/actions.cc
index 67d8b24..764cb6c 100644
--- a/aos/actions/actions.cc
+++ b/aos/actions/actions.cc
@@ -46,10 +46,10 @@
 
 bool ActionQueue::Running() { return static_cast<bool>(current_action_); }
 
-bool ActionQueue::GetCurrentActionState(bool* has_started, bool* sent_started,
-                                        bool* sent_cancel, bool* interrupted,
-                                        uint32_t* run_value,
-                                        uint32_t* old_run_value) {
+bool ActionQueue::GetCurrentActionState(bool *has_started, bool *sent_started,
+                                        bool *sent_cancel, bool *interrupted,
+                                        uint32_t *run_value,
+                                        uint32_t *old_run_value) {
   if (current_action_) {
     current_action_->GetState(has_started, sent_started, sent_cancel,
                               interrupted, run_value, old_run_value);
@@ -58,10 +58,10 @@
   return false;
 }
 
-bool ActionQueue::GetNextActionState(bool* has_started, bool* sent_started,
-                                     bool* sent_cancel, bool* interrupted,
-                                     uint32_t* run_value,
-                                     uint32_t* old_run_value) {
+bool ActionQueue::GetNextActionState(bool *has_started, bool *sent_started,
+                                     bool *sent_cancel, bool *interrupted,
+                                     uint32_t *run_value,
+                                     uint32_t *old_run_value) {
   if (next_action_) {
     next_action_->GetState(has_started, sent_started, sent_cancel, interrupted,
                            run_value, old_run_value);
diff --git a/aos/aos_cli_utils.cc b/aos/aos_cli_utils.cc
index f71ed2a..970797a 100644
--- a/aos/aos_cli_utils.cc
+++ b/aos/aos_cli_utils.cc
@@ -36,16 +36,19 @@
     bool expect_args) {
   // Don't generate failure output if the config doesn't exist while attempting
   // to autocomplete.
-  if (struct stat file_stat;
-      FLAGS__bash_autocomplete &&
-      (!(EndsWith(FLAGS_config, ".json") || EndsWith(FLAGS_config, ".bfbs")) ||
-       stat(FLAGS_config.c_str(), &file_stat) != 0 ||
-       (file_stat.st_mode & S_IFMT) != S_IFREG)) {
+  if (FLAGS__bash_autocomplete &&
+      (!(EndsWith(FLAGS_config, ".json") || EndsWith(FLAGS_config, ".bfbs")))) {
     std::cout << "COMPREPLY=()";
     return true;
   }
 
-  config.emplace(aos::configuration::ReadConfig(FLAGS_config));
+  config = aos::configuration::MaybeReadConfig(FLAGS_config);
+  if (FLAGS__bash_autocomplete && !config.has_value()) {
+    std::cout << "COMPREPLY=()";
+    return true;
+  }
+  CHECK(config.has_value()) << "Could not read config. See above errors.";
+
   event_loop.emplace(&config->message());
   event_loop->SkipTimingReport();
   event_loop->SkipAosLog();
diff --git a/aos/aos_graph_nodes.cc b/aos/aos_graph_nodes.cc
index cf7bc11..9c78c76 100644
--- a/aos/aos_graph_nodes.cc
+++ b/aos/aos_graph_nodes.cc
@@ -96,8 +96,8 @@
 
   // Write out all the nodes at the end, with their respective colors
   for (const auto &node_color : color_map) {
-    graph_out << "\t\"" << node_color.first << "\" [color=\"" << node_color.second
-              << "\"];" << std::endl;
+    graph_out << "\t\"" << node_color.first << "\" [color=\""
+              << node_color.second << "\"];" << std::endl;
   }
 
   // Close out the file
diff --git a/aos/condition_test.cc b/aos/condition_test.cc
index b49f27c..9250846 100644
--- a/aos/condition_test.cc
+++ b/aos/condition_test.cc
@@ -1,25 +1,24 @@
 #include "aos/condition.h"
 
-#include <unistd.h>
 #include <sys/types.h>
 #include <sys/wait.h>
+#include <unistd.h>
 
 #include <atomic>
 #include <chrono>
 #include <thread>
 
-#include "gtest/gtest.h"
-
-#include "aos/time/time.h"
-#include "aos/mutex/mutex.h"
-#include "aos/testing/test_shm.h"
-#include "aos/type_traits/type_traits.h"
+#include "aos/die.h"
+#include "aos/ipc_lib/aos_sync.h"
 #include "aos/ipc_lib/core_lib.h"
 #include "aos/logging/logging.h"
 #include "aos/macros.h"
-#include "aos/ipc_lib/aos_sync.h"
-#include "aos/die.h"
+#include "aos/mutex/mutex.h"
 #include "aos/testing/prevent_exit.h"
+#include "aos/testing/test_shm.h"
+#include "aos/time/time.h"
+#include "aos/type_traits/type_traits.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace testing {
@@ -102,18 +101,14 @@
   ConditionTest() : shared_(static_cast<Shared *>(shm_malloc(sizeof(Shared)))) {
     new (shared_) Shared();
   }
-  ~ConditionTest() {
-    shared_->~Shared();
-  }
+  ~ConditionTest() { shared_->~Shared(); }
 
   ::aos::testing::TestSharedMemory my_shm_;
 
   Shared *const shared_;
 
  protected:
-  void SetUp() override {
-    SetDieTestMode(true);
-  }
+  void SetUp() override { SetDieTestMode(true); }
 
  private:
   DISALLOW_COPY_AND_ASSIGN(ConditionTest);
@@ -123,8 +118,8 @@
  public:
   enum class Action {
     kWaitLockStart,  // lock, delay, wait, unlock
-    kWait,  // delay, lock, wait, unlock
-    kWaitNoUnlock,  // delay, lock, wait
+    kWait,           // delay, lock, wait, unlock
+    kWaitNoUnlock,   // delay, lock, wait
   };
 
   // This amount gets added to any passed in delay to make the test repeatable.
@@ -146,9 +141,7 @@
         shared_(static_cast<Shared *>(shm_malloc(sizeof(Shared)))) {
     new (shared_) Shared();
   }
-  ~ConditionTestProcess() {
-    AOS_CHECK_EQ(child_, -1);
-  }
+  ~ConditionTestProcess() { AOS_CHECK_EQ(child_, -1); }
 
   void Start() {
     ASSERT_FALSE(shared_->started);
@@ -167,9 +160,7 @@
     }
   }
 
-  bool IsFinished() {
-    return shared_->finished;
-  }
+  bool IsFinished() { return shared_->finished; }
 
   ::testing::AssertionResult Hung() {
     if (!shared_->started) {
@@ -346,8 +337,10 @@
   ConditionTestProcess child3(chrono::milliseconds(0),
                               ConditionTestProcess::Action::kWait,
                               &shared_->condition);
-  auto number_finished = [&]() { return (child1.IsFinished() ? 1 : 0) +
-    (child2.IsFinished() ? 1 : 0) + (child3.IsFinished() ? 1 : 0); };
+  auto number_finished = [&]() {
+    return (child1.IsFinished() ? 1 : 0) + (child2.IsFinished() ? 1 : 0) +
+           (child3.IsFinished() ? 1 : 0);
+  };
   child1.Start();
   child2.Start();
   child3.Start();
diff --git a/aos/configuration.cc b/aos/configuration.cc
index bc50d30..ed99e2a 100644
--- a/aos/configuration.cc
+++ b/aos/configuration.cc
@@ -169,7 +169,7 @@
   return absl::StrJoin(split, "/");
 }
 
-FlatbufferDetachedBuffer<Configuration> ReadConfig(
+std::optional<FlatbufferDetachedBuffer<Configuration>> MaybeReadConfig(
     const std::string_view path, absl::btree_set<std::string> *visited_paths,
     const std::vector<std::string_view> &extra_import_paths) {
   std::string binary_path = MaybeReplaceExtension(path, ".json", ".bfbs");
@@ -181,11 +181,12 @@
   // instead.  It is much faster to load .bfbs files than .json files.
   if (!binary_path_exists && !util::PathExists(raw_path)) {
     const bool path_is_absolute = raw_path.size() > 0 && raw_path[0] == '/';
-    if (path_is_absolute) {
-      CHECK(extra_import_paths.empty())
+    if (path_is_absolute && !extra_import_paths.empty()) {
+      LOG(ERROR)
           << "Can't specify extra import paths if attempting to read a config "
              "file from an absolute path (path is "
           << raw_path << ").";
+      return std::nullopt;
     }
 
     bool found_path = false;
@@ -204,11 +205,15 @@
         break;
       }
     }
-    CHECK(found_path) << ": Failed to find file " << path << ".";
+    if (!found_path) {
+      LOG(ERROR) << ": Failed to find file " << path << ".";
+      return std::nullopt;
+    }
   }
 
-  FlatbufferDetachedBuffer<Configuration> config = ReadConfigFile(
-      binary_path_exists ? binary_path : raw_path, binary_path_exists);
+  std::optional<FlatbufferDetachedBuffer<Configuration>> config =
+      ReadConfigFile(binary_path_exists ? binary_path : raw_path,
+                     binary_path_exists);
 
   // Depth first.  Take the following example:
   //
@@ -252,15 +257,16 @@
     LOG(FATAL)
         << "Already imported " << path << " (i.e. " << absolute_path
         << "). See above for the files that have already been processed.";
+    return std::nullopt;
   }
 
-  if (config.message().has_imports()) {
+  if (config->message().has_imports()) {
     // Capture the imports.
     const flatbuffers::Vector<flatbuffers::Offset<flatbuffers::String>> *v =
-        config.message().imports();
+        config->message().imports();
 
     // And then wipe them.  This gets GCed when we merge later.
-    config.mutable_message()->clear_imports();
+    config->mutable_message()->clear_imports();
 
     // Start with an empty configuration to merge into.
     FlatbufferDetachedBuffer<Configuration> merged_config =
@@ -271,14 +277,17 @@
       const std::string included_config =
           path_folder + "/" + std::string(str->string_view());
 
+      const auto optional_config =
+          MaybeReadConfig(included_config, visited_paths, extra_import_paths);
+      if (!optional_config.has_value()) {
+        return std::nullopt;
+      }
       // And them merge everything in.
-      merged_config = MergeFlatBuffers(
-          merged_config,
-          ReadConfig(included_config, visited_paths, extra_import_paths));
+      merged_config = MergeFlatBuffers(merged_config, *optional_config);
     }
 
     // Finally, merge this file in.
-    config = MergeFlatBuffers(merged_config, config);
+    config = MergeFlatBuffers(merged_config, *config);
   }
   return config;
 }
@@ -701,7 +710,7 @@
   return result;
 }
 
-FlatbufferDetachedBuffer<Configuration> ReadConfig(
+std::optional<FlatbufferDetachedBuffer<Configuration>> MaybeReadConfig(
     const std::string_view path,
     const std::vector<std::string_view> &extra_import_paths) {
   // Add the executable directory to the search path.  That makes it so that
@@ -726,17 +735,29 @@
 
   // We only want to read a file once.  So track the visited files in a set.
   absl::btree_set<std::string> visited_paths;
-  FlatbufferDetachedBuffer<Configuration> read_config =
-      ReadConfig(path, &visited_paths, extra_import_paths_with_exe);
+  std::optional<FlatbufferDetachedBuffer<Configuration>> read_config =
+      MaybeReadConfig(path, &visited_paths, extra_import_paths_with_exe);
+
+  if (read_config == std::nullopt) {
+    return read_config;
+  }
 
   // If we only read one file, and it had a .bfbs extension, it has to be a
   // fully formatted config.  Do a quick verification and return it.
   if (visited_paths.size() == 1 && EndsWith(*visited_paths.begin(), ".bfbs")) {
-    ValidateConfiguration(read_config);
+    ValidateConfiguration(*read_config);
     return read_config;
   }
 
-  return MergeConfiguration(read_config);
+  return MergeConfiguration(*read_config);
+}
+
+FlatbufferDetachedBuffer<Configuration> ReadConfig(
+    const std::string_view path,
+    const std::vector<std::string_view> &extra_import_paths) {
+  auto optional_config = MaybeReadConfig(path, extra_import_paths);
+  CHECK(optional_config) << "Could not read config. See above errors";
+  return std::move(*optional_config);
 }
 
 FlatbufferDetachedBuffer<Configuration> MergeWithConfig(
diff --git a/aos/configuration.h b/aos/configuration.h
index c0e2715..cb52d09 100644
--- a/aos/configuration.h
+++ b/aos/configuration.h
@@ -18,11 +18,17 @@
 namespace configuration {
 
 // Reads a json configuration.  This includes all imports and merges.  Note:
-// duplicate imports will result in a CHECK.
+// duplicate imports or invalid paths will result in a FATAL.
 FlatbufferDetachedBuffer<Configuration> ReadConfig(
     const std::string_view path,
     const std::vector<std::string_view> &extra_import_paths = {});
 
+// Reads a json configuration.  This includes all imports and merges. Returns
+// std::nullopt on duplicate imports or invalid paths.
+std::optional<FlatbufferDetachedBuffer<Configuration>> MaybeReadConfig(
+    const std::string_view path,
+    const std::vector<std::string_view> &extra_import_paths = {});
+
 // Sorts and merges entries in a config.
 FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
     const Flatbuffer<Configuration> &config);
diff --git a/aos/configuration_test.cc b/aos/configuration_test.cc
index f5081d2..b493058 100644
--- a/aos/configuration_test.cc
+++ b/aos/configuration_test.cc
@@ -95,6 +95,23 @@
       "aos/testdata/config1_bad.json");
 }
 
+// Tests that we die when we give an invalid path.
+TEST_F(ConfigurationDeathTest, NonexistentFile) {
+  EXPECT_DEATH(
+      {
+        FlatbufferDetachedBuffer<Configuration> config =
+            ReadConfig("nonexistent/config.json");
+      },
+      "above error");
+}
+
+// Tests that we return std::nullopt when we give an invalid path.
+TEST_F(ConfigurationTest, NonexistentFileOptional) {
+  std::optional<FlatbufferDetachedBuffer<Configuration>> config =
+      MaybeReadConfig("nonexistent/config.json");
+  EXPECT_FALSE(config.has_value());
+}
+
 // Tests that we reject invalid channel names.  This means any channels with //
 // in their name, a trailing /, or regex characters.
 TEST_F(ConfigurationDeathTest, InvalidChannelName) {
@@ -891,8 +908,8 @@
 TEST_F(ConfigurationDeathTest, InvalidLoggerConfig) {
   EXPECT_DEATH(
       {
-        FlatbufferDetachedBuffer<Configuration> config =
-            ReadConfig(ArtifactPath("aos/testdata/invalid_logging_configuration.json"));
+        FlatbufferDetachedBuffer<Configuration> config = ReadConfig(
+            ArtifactPath("aos/testdata/invalid_logging_configuration.json"));
       },
       "Logging timestamps without data");
 }
diff --git a/aos/containers/priority_queue.h b/aos/containers/priority_queue.h
index 8fb5e5c..b092219 100644
--- a/aos/containers/priority_queue.h
+++ b/aos/containers/priority_queue.h
@@ -96,6 +96,7 @@
   size_t next_idx(size_t idx) const { return list_[idx].upper_idx; }
   // Gets the index of the previous (lower valued) element in the queue.
   size_t prev_idx(size_t idx) const { return list_[idx].lower_idx; }
+
  private:
   struct Datum {
     // A list element with data and the indices of the next highest/lowest
diff --git a/aos/containers/priority_queue_test.cc b/aos/containers/priority_queue_test.cc
index c05d827..d26d7c9 100644
--- a/aos/containers/priority_queue_test.cc
+++ b/aos/containers/priority_queue_test.cc
@@ -17,6 +17,7 @@
 class PriorityQueueTest : public ::testing::Test {
  public:
   PriorityQueueTest() {}
+
  protected:
   PriorityQueue<int, 10, ExampleCompare> queue_;
 };
diff --git a/aos/containers/sized_array_test.cc b/aos/containers/sized_array_test.cc
index d182ad2..47be950 100644
--- a/aos/containers/sized_array_test.cc
+++ b/aos/containers/sized_array_test.cc
@@ -159,7 +159,7 @@
   EXPECT_EQ(a.capacity(), 4u);
   EXPECT_TRUE(a.empty());
 
-  const int* const pre_front = a.data();
+  const int *const pre_front = a.data();
   a.assign({1, 2, 3, 4});
 
   EXPECT_EQ(a.capacity(), 4u);
diff --git a/aos/events/epoll_test.cc b/aos/events/epoll_test.cc
index 053a09b..b725747 100644
--- a/aos/events/epoll_test.cc
+++ b/aos/events/epoll_test.cc
@@ -129,9 +129,7 @@
   // epoll_ctl manpage, this should trigger an error).
   Pipe pipe;
   int number_errors = 0;
-  epoll_.OnError(pipe.write_fd(), [&]() {
-    ++number_errors;
-  });
+  epoll_.OnError(pipe.write_fd(), [&]() { ++number_errors; });
 
   // Sanity check that we *don't* get any errors before anything interesting has
   // happened.
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
index 984a006..8c16f3a 100644
--- a/aos/events/event_loop.h
+++ b/aos/events/event_loop.h
@@ -139,7 +139,10 @@
  public:
   using SharedSpan = std::shared_ptr<const absl::Span<const uint8_t>>;
 
-  enum class [[nodiscard]] Error {
+  // This looks a little ugly with no space, but please leave it so clang-format
+  // doesn't keep changing it. Bug is filed at
+  // <https://github.com/llvm/llvm-project/issues/55457>.
+  enum class [[nodiscard]] Error{
       // Represents success and no error
       kOk,
 
@@ -147,7 +150,7 @@
       // frequency and channel storage duration allow
       kMessagesSentTooFast,
       // Access to Redzone was attempted in Sender Queue
-      kInvalidRedzone
+      kInvalidRedzone,
   };
 
   RawSender(EventLoop *event_loop, const Channel *channel);
diff --git a/aos/events/event_scheduler.h b/aos/events/event_scheduler.h
index b64728c..d91a75e 100644
--- a/aos/events/event_scheduler.h
+++ b/aos/events/event_scheduler.h
@@ -347,8 +347,9 @@
 inline monotonic_clock::time_point EventScheduler::monotonic_now() const {
   const logger::BootTimestamp t =
       FromDistributedClock(scheduler_scheduler_->distributed_now());
-  CHECK_EQ(t.boot, boot_count_) << ": " << " " << t << " d "
-                                << scheduler_scheduler_->distributed_now();
+  CHECK_EQ(t.boot, boot_count_)
+      << ": "
+      << " " << t << " d " << scheduler_scheduler_->distributed_now();
   return t.time;
 }
 
diff --git a/aos/events/logging/boot_timestamp.cc b/aos/events/logging/boot_timestamp.cc
index b3511f4..ef65171 100644
--- a/aos/events/logging/boot_timestamp.cc
+++ b/aos/events/logging/boot_timestamp.cc
@@ -19,8 +19,8 @@
 
 std::ostream &operator<<(std::ostream &os,
                          const struct BootQueueIndex &queue_index) {
-  return os << "{.boot=" << queue_index.boot
-            << ", .index=" << queue_index.index << "}";
+  return os << "{.boot=" << queue_index.boot << ", .index=" << queue_index.index
+            << "}";
 }
 
 }  // namespace aos::logger
diff --git a/aos/events/logging/buffer_encoder_param_test.h b/aos/events/logging/buffer_encoder_param_test.h
index fd1a00c..871e25e 100644
--- a/aos/events/logging/buffer_encoder_param_test.h
+++ b/aos/events/logging/buffer_encoder_param_test.h
@@ -6,12 +6,11 @@
 #include <random>
 #include <vector>
 
-#include "glog/logging.h"
-#include "gtest/gtest.h"
-
 #include "aos/events/logging/logfile_utils.h"
 #include "aos/events/logging/logger_generated.h"
 #include "aos/testing/random_seed.h"
+#include "glog/logging.h"
+#include "gtest/gtest.h"
 
 namespace aos::logger::testing {
 
diff --git a/aos/events/logging/buffer_encoder_test.cc b/aos/events/logging/buffer_encoder_test.cc
index 0687f83..5a9b85f 100644
--- a/aos/events/logging/buffer_encoder_test.cc
+++ b/aos/events/logging/buffer_encoder_test.cc
@@ -4,12 +4,11 @@
 #include <fstream>
 #include <string>
 
+#include "aos/events/logging/buffer_encoder_param_test.h"
 #include "glog/logging.h"
 #include "gmock/gmock.h"
 #include "gtest/gtest.h"
 
-#include "aos/events/logging/buffer_encoder_param_test.h"
-
 namespace aos::logger::testing {
 
 class DummyEncoderTest : public BufferEncoderBaseTest {};
diff --git a/aos/events/logging/log_cat.cc b/aos/events/logging/log_cat.cc
index 2b6fe3e..3e1dd1e 100644
--- a/aos/events/logging/log_cat.cc
+++ b/aos/events/logging/log_cat.cc
@@ -28,6 +28,8 @@
             "If true, just print the data out unsorted and unparsed");
 DEFINE_string(raw_header, "",
               "If set, the file to read the header from in raw mode");
+DEFINE_bool(distributed_clock, false,
+            "If true, print out the distributed time");
 DEFINE_bool(format_raw, true,
             "If true and --raw is specified, print out raw data, but use the "
             "schema to format the data.");
@@ -80,8 +82,9 @@
 // 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
 // independent of any debugging information on stderr.
-void PrintMessage(const std::string_view node_name, const aos::Channel *channel,
-                  const aos::Context &context,
+void PrintMessage(const std::string_view node_name,
+                  aos::NodeEventLoopFactory *node_factory,
+                  const aos::Channel *channel, const aos::Context &context,
                   aos::FastStringBuilder *builder) {
   builder->Reset();
   CHECK(flatbuffers::Verify(*channel->schema(),
@@ -116,6 +119,11 @@
               << aos::configuration::StrippedChannelToString(channel)
               << ", \"data\": " << *builder << "}" << std::endl;
   } else {
+    if (FLAGS_distributed_clock) {
+      std::cout << node_factory->ToDistributedClock(
+                       context.monotonic_event_time)
+                << " ";
+    }
     if (!node_name.empty()) {
       std::cout << node_name << " ";
     }
@@ -265,6 +273,7 @@
               aos::SimulatedEventLoopFactory *factory,
               aos::FastStringBuilder *builder)
       : factory_(factory),
+        node_factory_(factory->GetNodeEventLoopFactory(event_loop->node())),
         event_loop_(event_loop),
         message_print_counter_(message_print_counter),
         node_name_(
@@ -306,29 +315,29 @@
         VLOG(1) << "Listening on " << name << " " << type;
 
         CHECK_NOTNULL(channel->schema());
-        event_loop_->MakeRawWatcher(
-            channel,
-            [this, channel, start_time, end_time](const aos::Context &context,
-                                                  const void * /*message*/) {
-              if (!FLAGS_print) {
-                return;
-              }
+        event_loop_->MakeRawWatcher(channel, [this, channel, start_time,
+                                              end_time](
+                                                 const aos::Context &context,
+                                                 const void * /*message*/) {
+          if (!FLAGS_print) {
+            return;
+          }
 
-              if (!FLAGS_fetch && !started_) {
-                return;
-              }
+          if (!FLAGS_fetch && !started_) {
+            return;
+          }
 
-              if (context.monotonic_event_time < start_time ||
-                  context.monotonic_event_time > end_time) {
-                return;
-              }
+          if (context.monotonic_event_time < start_time ||
+              context.monotonic_event_time > end_time) {
+            return;
+          }
 
-              PrintMessage(node_name_, channel, context, builder_);
-              ++(*message_print_counter_);
-              if (FLAGS_count > 0 && *message_print_counter_ >= FLAGS_count) {
-                factory_->Exit();
-              }
-            });
+          PrintMessage(node_name_, node_factory_, channel, context, builder_);
+          ++(*message_print_counter_);
+          if (FLAGS_count > 0 && *message_print_counter_ >= FLAGS_count) {
+            factory_->Exit();
+          }
+        });
       }
     }
   }
@@ -365,6 +374,7 @@
   };
 
   aos::SimulatedEventLoopFactory *factory_;
+  aos::NodeEventLoopFactory *node_factory_;
   aos::EventLoop *event_loop_;
 
   uint64_t *message_print_counter_ = nullptr;
diff --git a/aos/events/logging/log_namer.cc b/aos/events/logging/log_namer.cc
index f269f43..6fd39f8 100644
--- a/aos/events/logging/log_namer.cc
+++ b/aos/events/logging/log_namer.cc
@@ -268,7 +268,7 @@
   const UUID &source_node_boot_uuid = state[node_index].boot_uuid;
   const Node *const source_node =
       configuration::GetNode(configuration_, node_index);
-  CHECK_EQ(LogFileHeader::MiniReflectTypeTable()->num_elems, 32u);
+  CHECK_EQ(LogFileHeader::MiniReflectTypeTable()->num_elems, 34u);
   flatbuffers::FlatBufferBuilder fbb;
   fbb.ForceDefaults(true);
 
@@ -288,6 +288,14 @@
   CHECK(header_.message().has_name());
   const flatbuffers::Offset<flatbuffers::String> name_offset =
       fbb.CreateString(header_.message().name()->string_view());
+  const flatbuffers::Offset<flatbuffers::String> logger_sha1_offset =
+      header_.message().has_logger_sha1()
+          ? fbb.CreateString(header_.message().logger_sha1()->string_view())
+          : 0;
+  const flatbuffers::Offset<flatbuffers::String> logger_version_offset =
+      header_.message().has_logger_version()
+          ? fbb.CreateString(header_.message().logger_version()->string_view())
+          : 0;
 
   CHECK(header_.message().has_log_event_uuid());
   const flatbuffers::Offset<flatbuffers::String> log_event_uuid_offset =
@@ -441,6 +449,12 @@
   aos::logger::LogFileHeader::Builder log_file_header_builder(fbb);
 
   log_file_header_builder.add_name(name_offset);
+  if (!logger_sha1_offset.IsNull()) {
+    log_file_header_builder.add_logger_sha1(logger_sha1_offset);
+  }
+  if (!logger_version_offset.IsNull()) {
+    log_file_header_builder.add_logger_version(logger_version_offset);
+  }
 
   // Only add the node if we are running in a multinode configuration.
   if (!logger_node_offset.IsNull()) {
diff --git a/aos/events/logging/log_namer.h b/aos/events/logging/log_namer.h
index 4a1e74f..7947ebe 100644
--- a/aos/events/logging/log_namer.h
+++ b/aos/events/logging/log_namer.h
@@ -220,9 +220,7 @@
         UUID::FromString(header_.message().logger_node_boot_uuid());
   }
 
-  void ClearStartTimes() {
-    node_states_.clear();
-  }
+  void ClearStartTimes() { node_states_.clear(); }
 
   void SetStartTimes(size_t node_index, const UUID &boot_uuid,
                      monotonic_clock::time_point monotonic_start_time,
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index 196ac53..c1333c6 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -349,9 +349,8 @@
 
     // Sets the node event loop factory for replaying into a
     // SimulatedEventLoopFactory.  Returns the EventLoop to use.
-    void SetNodeEventLoopFactory(
-        NodeEventLoopFactory *node_event_loop_factory,
-        SimulatedEventLoopFactory *event_loop_factory);
+    void SetNodeEventLoopFactory(NodeEventLoopFactory *node_event_loop_factory,
+                                 SimulatedEventLoopFactory *event_loop_factory);
 
     // Sets and gets the event loop to use.
     void set_event_loop(EventLoop *event_loop) { event_loop_ = event_loop; }
diff --git a/aos/events/logging/log_stats.cc b/aos/events/logging/log_stats.cc
index cf11fa6..7c3511d 100644
--- a/aos/events/logging/log_stats.cc
+++ b/aos/events/logging/log_stats.cc
@@ -301,8 +301,7 @@
                     << "hz max";
         }
         std::cout << " " << channel_stats[i].avg_message_size()
-                  << " bytes avg, "
-                  << channel_stats[i].avg_message_bandwidth()
+                  << " bytes avg, " << channel_stats[i].avg_message_bandwidth()
                   << " bytes/sec avg, " << channel_stats[i].max_message_size()
                   << " bytes max / " << channel_stats[i].channel()->max_size()
                   << "bytes " << channel_stats[i].Percentile();
diff --git a/aos/events/logging/log_writer.cc b/aos/events/logging/log_writer.cc
index 2a53f05..0dc4468 100644
--- a/aos/events/logging/log_writer.cc
+++ b/aos/events/logging/log_writer.cc
@@ -658,6 +658,11 @@
   const flatbuffers::Offset<flatbuffers::String> name_offset =
       fbb.CreateString(name_);
 
+  const flatbuffers::Offset<flatbuffers::String> logger_sha1_offset =
+      logger_sha1_.empty() ? 0 : fbb.CreateString(logger_sha1_);
+  const flatbuffers::Offset<flatbuffers::String> logger_version_offset =
+      logger_version_.empty() ? 0 : fbb.CreateString(logger_version_);
+
   CHECK(log_event_uuid_ != UUID::Zero());
   const flatbuffers::Offset<flatbuffers::String> log_event_uuid_offset =
       log_event_uuid_.PackString(&fbb);
@@ -687,6 +692,12 @@
   aos::logger::LogFileHeader::Builder log_file_header_builder(fbb);
 
   log_file_header_builder.add_name(name_offset);
+  if (!logger_sha1_offset.IsNull()) {
+    log_file_header_builder.add_logger_sha1(logger_sha1_offset);
+  }
+  if (!logger_version_offset.IsNull()) {
+    log_file_header_builder.add_logger_version(logger_version_offset);
+  }
 
   // Only add the node if we are running in a multinode configuration.
   if (configuration::MultiNode(configuration_)) {
diff --git a/aos/events/logging/log_writer.h b/aos/events/logging/log_writer.h
index 7beef03..c364d36 100644
--- a/aos/events/logging/log_writer.h
+++ b/aos/events/logging/log_writer.h
@@ -43,6 +43,11 @@
   // Overrides the name in the log file header.
   void set_name(std::string_view name) { name_ = name; }
 
+  void set_logger_sha1(std::string_view sha1) { logger_sha1_ = sha1; }
+  void set_logger_version(std::string_view version) {
+    logger_version_ = version;
+  }
+
   // Sets the callback to run after each period of data is logged. Defaults to
   // doing nothing.
   //
@@ -130,8 +135,9 @@
 
   // Restart logging using a new naming scheme. Intended for log rotation.
   // Returns a unique_ptr to the prior log_namer instance.
-  std::unique_ptr<LogNamer> RestartLogging(std::unique_ptr<LogNamer> log_namer,
-                    std::optional<UUID> log_start_uuid = std::nullopt);
+  std::unique_ptr<LogNamer> RestartLogging(
+      std::unique_ptr<LogNamer> log_namer,
+      std::optional<UUID> log_start_uuid = std::nullopt);
 
   // Moves the current log location to the new name. Returns true if a change
   // was made, false otherwise.
@@ -222,7 +228,7 @@
   std::vector<int> event_loop_to_logged_channel_index_;
 
   // Start/Restart write configuration into LogNamer space.
-  std::string WriteConfiguration(LogNamer* log_namer);
+  std::string WriteConfiguration(LogNamer *log_namer);
 
   void WriteHeader(aos::monotonic_clock::time_point monotonic_start_time =
                        aos::monotonic_clock::min_time,
@@ -244,7 +250,8 @@
   void WriteMissingTimestamps();
 
   void WriteData(NewDataWriter *writer, const FetcherStruct &f);
-  void WriteTimestamps(NewDataWriter *timestamps_writer, const FetcherStruct &f);
+  void WriteTimestamps(NewDataWriter *timestamps_writer,
+                       const FetcherStruct &f);
   void WriteContent(NewDataWriter *contents_writer, const FetcherStruct &f);
 
   void WriteFetchedRecord(FetcherStruct &f);
@@ -289,6 +296,8 @@
 
   // Name to save in the log file.  Defaults to hostname.
   std::string name_;
+  std::string logger_sha1_;
+  std::string logger_version_;
 
   std::function<void()> on_logged_period_ = []() {};
 
diff --git a/aos/events/logging/logfile_sorting.cc b/aos/events/logging/logfile_sorting.cc
index e0c378e..82b4684 100644
--- a/aos/events/logging/logfile_sorting.cc
+++ b/aos/events/logging/logfile_sorting.cc
@@ -93,7 +93,7 @@
 }
 
 bool ConfigOnly(const LogFileHeader *header) {
-  CHECK_EQ(LogFileHeader::MiniReflectTypeTable()->num_elems, 32u);
+  CHECK_EQ(LogFileHeader::MiniReflectTypeTable()->num_elems, 34u);
   if (header->has_monotonic_start_time()) return false;
   if (header->has_realtime_start_time()) return false;
   if (header->has_max_out_of_order_duration()) return false;
@@ -123,6 +123,8 @@
     return false;
   if (header->has_oldest_logger_local_unreliable_monotonic_timestamps())
     return false;
+  if (header->has_logger_sha1()) return false;
+  if (header->has_logger_version()) return false;
 
   return header->has_configuration();
 }
@@ -219,6 +221,10 @@
   // Name from a log.  All logs below have been confirmed to match.
   std::string name;
 
+  // Logger version info from the log.
+  std::string logger_sha1;
+  std::string logger_version;
+
   // Mapping from parts_uuid, source_boot_uuid -> parts.  We have log files
   // where the parts_uuid stays constant across reboots.
   std::map<std::pair<std::string, std::string>, UnsortedLogParts>
@@ -411,6 +417,16 @@
             ? log_header->message().name()->string_view()
             : "";
 
+    const std::string_view logger_sha1 =
+        log_header->message().has_logger_sha1()
+            ? log_header->message().logger_sha1()->string_view()
+            : "";
+
+    const std::string_view logger_version =
+        log_header->message().has_logger_version()
+            ? log_header->message().logger_version()->string_view()
+            : "";
+
     const std::string_view logger_node =
         log_header->message().has_logger_node()
             ? log_header->message().logger_node()->name()->string_view()
@@ -557,12 +573,16 @@
       log_it->second.log_start_uuid = log_start_uuid;
       log_it->second.logger_instance_uuid = logger_instance_uuid;
       log_it->second.name = name;
+      log_it->second.logger_sha1 = logger_sha1;
+      log_it->second.logger_version = logger_version;
     } else {
       CHECK_EQ(log_it->second.logger_node, logger_node);
       CHECK_EQ(log_it->second.logger_boot_uuid, logger_boot_uuid);
       CHECK_EQ(log_it->second.log_start_uuid, log_start_uuid);
       CHECK_EQ(log_it->second.logger_instance_uuid, logger_instance_uuid);
       CHECK_EQ(log_it->second.name, name);
+      CHECK_EQ(log_it->second.logger_sha1, logger_sha1);
+      CHECK_EQ(log_it->second.logger_version, logger_version);
     }
 
     if (node == log_it->second.logger_node) {
@@ -1825,6 +1845,8 @@
     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;
+    new_file.logger_sha1 = logs.second.logger_sha1;
+    new_file.logger_version = logs.second.logger_version;
     new_file.corrupted = corrupted;
     new_file.boots = boot_counts;
     bool seen_part = false;
@@ -1994,6 +2016,15 @@
   if (!file.log_start_uuid.empty()) {
     stream << " \"log_start_uuid\": \"" << file.log_start_uuid << "\",\n";
   }
+  if (!file.name.empty()) {
+    stream << " \"name\": \"" << file.name << "\",\n";
+  }
+  if (!file.logger_sha1.empty()) {
+    stream << " \"logger_sha1\": \"" << file.logger_sha1 << "\",\n";
+  }
+  if (!file.logger_version.empty()) {
+    stream << " \"logger_version\": \"" << file.logger_version << "\",\n";
+  }
   stream << " \"config\": \"" << file.config.get() << "\"";
   if (!file.config_sha256.empty()) {
     stream << ",\n \"config_sha256\": \"" << file.config_sha256 << "\"";
diff --git a/aos/events/logging/logfile_sorting.h b/aos/events/logging/logfile_sorting.h
index 6e4b9b4..9e99bb2 100644
--- a/aos/events/logging/logfile_sorting.h
+++ b/aos/events/logging/logfile_sorting.h
@@ -110,6 +110,10 @@
   // The name field in the log file headers.
   std::string name;
 
+  // The logger version info in the logfile headers, if available.
+  std::string logger_sha1;
+  std::string logger_version;
+
   // All the parts, unsorted.
   std::vector<LogParts> parts;
 
diff --git a/aos/events/logging/logfile_utils.cc b/aos/events/logging/logfile_utils.cc
index ecdf5d6..01f3002 100644
--- a/aos/events/logging/logfile_utils.cc
+++ b/aos/events/logging/logfile_utils.cc
@@ -558,8 +558,8 @@
     }
 
     if (span_reader_.IsIncomplete()) {
-      LOG(ERROR) << "Unable to access some messages in " << filename()
-                 << " : " << span_reader_.TotalRead() << " bytes read, "
+      LOG(ERROR) << "Unable to access some messages in " << filename() << " : "
+                 << span_reader_.TotalRead() << " bytes read, "
                  << span_reader_.TotalConsumed() << " bytes usable."
                  << std::endl;
     }
@@ -570,15 +570,14 @@
 
   if (crash_on_corrupt_message_flag_) {
     CHECK(msg.Verify()) << "Corrupted message at offset "
-                        << total_verified_before_
-                        << " found within " << filename()
+                        << total_verified_before_ << " found within "
+                        << filename()
                         << "; set --nocrash_on_corrupt_message to see summary;"
                         << " also set --ignore_corrupt_messages to process"
                         << " anyway";
 
   } else if (!msg.Verify()) {
-    LOG(ERROR) << "Corrupted message at offset "
-               << total_verified_before_
+    LOG(ERROR) << "Corrupted message at offset " << total_verified_before_
                << " from " << filename() << std::endl;
 
     total_corrupted_ += msg_data.size();
@@ -922,14 +921,13 @@
       size_t monotonic_remote_boot = 0xffffff;
 
       if (m->monotonic_remote_time.has_value()) {
-        const Node *node = parts().config->nodes()->Get(
-            source_node_index_[m->channel_index]);
+        const Node *node =
+            parts().config->nodes()->Get(source_node_index_[m->channel_index]);
 
         std::optional<size_t> boot = parts_message_reader_.boot_count(
             source_node_index_[m->channel_index]);
         CHECK(boot) << ": Failed to find boot for node " << MaybeNodeName(node)
-                    << ", with index "
-                    << source_node_index_[m->channel_index];
+                    << ", with index " << source_node_index_[m->channel_index];
         monotonic_remote_boot = *boot;
       }
 
@@ -1242,16 +1240,16 @@
 }
 
 void TimestampMapper::QueueMessage(Message *m) {
-  matched_messages_.emplace_back(TimestampedMessage{
-      .channel_index = m->channel_index,
-      .queue_index = m->queue_index,
-      .monotonic_event_time = m->timestamp,
-      .realtime_event_time = m->data->realtime_sent_time,
-      .remote_queue_index = BootQueueIndex::Invalid(),
-      .monotonic_remote_time = BootTimestamp::min_time(),
-      .realtime_remote_time = realtime_clock::min_time,
-      .monotonic_timestamp_time = BootTimestamp::min_time(),
-      .data = std::move(m->data)});
+  matched_messages_.emplace_back(
+      TimestampedMessage{.channel_index = m->channel_index,
+                         .queue_index = m->queue_index,
+                         .monotonic_event_time = m->timestamp,
+                         .realtime_event_time = m->data->realtime_sent_time,
+                         .remote_queue_index = BootQueueIndex::Invalid(),
+                         .monotonic_remote_time = BootTimestamp::min_time(),
+                         .realtime_remote_time = realtime_clock::min_time,
+                         .monotonic_timestamp_time = BootTimestamp::min_time(),
+                         .data = std::move(m->data)});
 }
 
 TimestampedMessage *TimestampMapper::Front() {
@@ -1448,13 +1446,12 @@
 
   if (remote_queue_index < data_queue->front().queue_index ||
       remote_queue_index > data_queue->back().queue_index) {
-    return Message{
-        .channel_index = message.channel_index,
-        .queue_index = remote_queue_index,
-        .timestamp = monotonic_remote_time,
-        .monotonic_remote_boot = 0xffffff,
-        .monotonic_timestamp_boot = 0xffffff,
-        .data = nullptr};
+    return Message{.channel_index = message.channel_index,
+                   .queue_index = remote_queue_index,
+                   .timestamp = monotonic_remote_time,
+                   .monotonic_remote_boot = 0xffffff,
+                   .monotonic_timestamp_boot = 0xffffff,
+                   .data = nullptr};
   }
 
   // The algorithm below is constant time with some assumptions.  We need there
diff --git a/aos/events/logging/logfile_utils.h b/aos/events/logging/logfile_utils.h
index 41d4a9a..ca733d4 100644
--- a/aos/events/logging/logfile_utils.h
+++ b/aos/events/logging/logfile_utils.h
@@ -208,8 +208,9 @@
 
   size_t TotalRead() const { return total_read_; }
   size_t TotalConsumed() const { return total_consumed_; }
-  bool IsIncomplete() const { return is_finished_
-      && total_consumed_ < total_read_; }
+  bool IsIncomplete() const {
+    return is_finished_ && total_consumed_ < total_read_;
+  }
 
   // Returns a span with the data for the next message from the log file,
   // including the size.  The result is only guarenteed to be valid until
@@ -630,7 +631,8 @@
 
   realtime_clock::time_point realtime_start_time_ = realtime_clock::max_time;
   monotonic_clock::time_point monotonic_start_time_ = monotonic_clock::max_time;
-  monotonic_clock::time_point monotonic_oldest_time_ = monotonic_clock::max_time;
+  monotonic_clock::time_point monotonic_oldest_time_ =
+      monotonic_clock::max_time;
 };
 
 // Class to concatenate multiple boots worth of logs into a single per-node
diff --git a/aos/events/logging/logfile_utils_out_of_space_test_runner.cc b/aos/events/logging/logfile_utils_out_of_space_test_runner.cc
index 3010a6f..b08bebb 100644
--- a/aos/events/logging/logfile_utils_out_of_space_test_runner.cc
+++ b/aos/events/logging/logfile_utils_out_of_space_test_runner.cc
@@ -2,11 +2,10 @@
 
 #include <array>
 
-#include "gflags/gflags.h"
-#include "glog/logging.h"
-
 #include "aos/events/logging/logfile_utils.h"
 #include "aos/init.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
 
 DECLARE_int32(flush_size);
 DEFINE_string(tmpfs, "", "tmpfs with the desired size");
diff --git a/aos/events/logging/logger.fbs b/aos/events/logging/logger.fbs
index 0fe6253..71a7b02 100644
--- a/aos/events/logging/logger.fbs
+++ b/aos/events/logging/logger.fbs
@@ -191,6 +191,13 @@
   // timestamps.
   oldest_logger_remote_unreliable_monotonic_timestamps:[int64] (id: 30);
   oldest_logger_local_unreliable_monotonic_timestamps:[int64] (id: 31);
+
+  // Logger build version.  This is normally the git sha1 that the logger was
+  // built from.
+  logger_sha1:string (id:32);
+  // Logger textual version.  This is normally the release name stamped into
+  // the binary.
+  logger_version:string (id:33);
 }
 
 // Table holding a message.
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index aee2883..ec273a8 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -556,6 +556,10 @@
     logger->set_polling_period(std::chrono::milliseconds(100));
     logger->set_name(
         absl::StrCat("name_prefix_", event_loop->node()->name()->str()));
+    logger->set_logger_sha1(
+        absl::StrCat("logger_sha1_", event_loop->node()->name()->str()));
+    logger->set_logger_version(
+        absl::StrCat("logger_version_", event_loop->node()->name()->str()));
     event_loop->OnRun([this, logfile_base]() {
       std::unique_ptr<MultiNodeLogNamer> namer =
           std::make_unique<MultiNodeLogNamer>(logfile_base, configuration,
@@ -991,6 +995,10 @@
       EXPECT_TRUE(log_file.config);
       EXPECT_EQ(log_file.name,
                 absl::StrCat("name_prefix_", log_file.logger_node));
+      EXPECT_EQ(log_file.logger_sha1,
+                absl::StrCat("logger_sha1_", log_file.logger_node));
+      EXPECT_EQ(log_file.logger_version,
+                absl::StrCat("logger_version_", log_file.logger_node));
 
       for (const LogParts &part : log_file.parts) {
         EXPECT_NE(part.monotonic_start_time, aos::monotonic_clock::min_time)
diff --git a/aos/events/logging/lzma_encoder.h b/aos/events/logging/lzma_encoder.h
index 7b7010a..4edd0e8 100644
--- a/aos/events/logging/lzma_encoder.h
+++ b/aos/events/logging/lzma_encoder.h
@@ -1,9 +1,9 @@
 #ifndef AOS_EVENTS_LOGGING_LZMA_ENCODER_H_
 #define AOS_EVENTS_LOGGING_LZMA_ENCODER_H_
 
-#include <string_view>
 #include <condition_variable>
 #include <mutex>
+#include <string_view>
 #include <thread>
 
 #include "absl/types/span.h"
diff --git a/aos/events/ping_lib.h b/aos/events/ping_lib.h
index 6107494..75d06e7 100644
--- a/aos/events/ping_lib.h
+++ b/aos/events/ping_lib.h
@@ -4,8 +4,8 @@
 #include <chrono>
 
 #include "aos/events/event_loop.h"
-#include "aos/events/pong_generated.h"
 #include "aos/events/ping_generated.h"
+#include "aos/events/pong_generated.h"
 
 namespace aos {
 
diff --git a/aos/events/pong_lib.h b/aos/events/pong_lib.h
index 0b50599..7dc20d5 100644
--- a/aos/events/pong_lib.h
+++ b/aos/events/pong_lib.h
@@ -2,8 +2,8 @@
 #define AOS_EVENTS_PONG_LIB_H_
 
 #include "aos/events/event_loop.h"
-#include "aos/events/pong_generated.h"
 #include "aos/events/ping_generated.h"
+#include "aos/events/pong_generated.h"
 
 namespace aos {
 
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index 4671f12..e6bc28d 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -962,7 +962,8 @@
 }
 
 std::optional<uint32_t> SimulatedChannel::Send(
-    std::shared_ptr<SimulatedMessage> message, CheckSentTooFast check_sent_too_fast) {
+    std::shared_ptr<SimulatedMessage> message,
+    CheckSentTooFast check_sent_too_fast) {
   const auto now = scheduler_->monotonic_now();
   // Remove times that are greater than or equal to a channel_storage_duration_
   // ago
@@ -1051,8 +1052,8 @@
   CHECK_LE(length, message_->context.size);
   message_->context.size = length;
 
-  const std::optional<uint32_t> optional_queue_index =
-      simulated_channel_->Send(message_, simulated_event_loop_->options().check_sent_too_fast);
+  const std::optional<uint32_t> optional_queue_index = simulated_channel_->Send(
+      message_, simulated_event_loop_->options().check_sent_too_fast);
 
   // Check that we are not sending messages too fast
   if (!optional_queue_index) {
diff --git a/aos/events/simulated_event_loop.h b/aos/events/simulated_event_loop.h
index 234afa0..9200044 100644
--- a/aos/events/simulated_event_loop.h
+++ b/aos/events/simulated_event_loop.h
@@ -212,13 +212,13 @@
   // args for the Main class.  Returns a pointer to the class that was started
   // if it was started, or nullptr.
   template <class Main, class... Args>
-  Main *MaybeStart(std::string_view name, Args &&... args);
+  Main *MaybeStart(std::string_view name, Args &&...args);
 
   // Starts an application regardless of if the config says to or not.  name is
   // the name of the application, and args are the constructor args for the
   // application.  Returns a pointer to the class that was started.
   template <class Main, class... Args>
-  Main *AlwaysStart(std::string_view name, Args &&... args);
+  Main *AlwaysStart(std::string_view name, Args &&...args);
 
   // Returns the simulated network delay for messages forwarded between nodes.
   std::chrono::nanoseconds network_delay() const {
@@ -326,7 +326,7 @@
     // application.
     template <class... Args>
     TypedApplication(NodeEventLoopFactory *node_factory, std::string_view name,
-                     Args &&... args)
+                     Args &&...args)
         : Application(node_factory, name),
           main(event_loop.get(), std::forward<Args>(args)...) {
       VLOG(1) << node_factory->scheduler_.distributed_now() << " "
@@ -345,7 +345,7 @@
 };
 
 template <class Main, class... Args>
-Main *NodeEventLoopFactory::MaybeStart(std::string_view name, Args &&... args) {
+Main *NodeEventLoopFactory::MaybeStart(std::string_view name, Args &&...args) {
   const aos::Application *application =
       configuration::GetApplication(configuration(), node(), name);
 
@@ -356,8 +356,7 @@
 }
 
 template <class Main, class... Args>
-Main *NodeEventLoopFactory::AlwaysStart(std::string_view name,
-                                        Args &&... args) {
+Main *NodeEventLoopFactory::AlwaysStart(std::string_view name, Args &&...args) {
   std::unique_ptr<TypedApplication<Main>> app =
       std::make_unique<TypedApplication<Main>>(this, name,
                                                std::forward<Args>(args)...);
diff --git a/aos/events/simulated_event_loop_test.cc b/aos/events/simulated_event_loop_test.cc
index 4b155ce..1a35b69 100644
--- a/aos/events/simulated_event_loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -246,7 +246,8 @@
   EXPECT_EQ(test_message_counter2.count(), 0u);
 }
 
-// Test that if we configure an event loop to be able to send too fast that we do allow it to do so.
+// Test that if we configure an event loop to be able to send too fast that we
+// do allow it to do so.
 TEST(SimulatedEventLoopTest, AllowSendTooFast) {
   SimulatedEventLoopTestFactory factory;
 
@@ -277,7 +278,8 @@
   // And now we should start being in the sending-too-fast phase.
   for (int ii = 0; ii < queue_size; ++ii) {
     ASSERT_EQ(SendTestMessage(too_fast_message_sender), RawSender::Error::kOk);
-    ASSERT_EQ(SendTestMessage(limited_message_sender), RawSender::Error::kMessagesSentTooFast);
+    ASSERT_EQ(SendTestMessage(limited_message_sender),
+              RawSender::Error::kMessagesSentTooFast);
   }
 }
 
@@ -309,7 +311,8 @@
   // This one should succeed now that the exclusive channel is removed.
   aos::Sender<TestMessage> normal_sender =
       normal_event_loop->MakeSender<TestMessage>("/test");
-  EXPECT_DEATH(exclusive_event_loop->MakeSender<TestMessage>("/test"), "TestMessage");
+  EXPECT_DEATH(exclusive_event_loop->MakeSender<TestMessage>("/test"),
+               "TestMessage");
 }
 
 void TestSentTooFastCheckEdgeCase(
diff --git a/aos/events/simulated_network_bridge.cc b/aos/events/simulated_network_bridge.cc
index c6ea811..19ca658 100644
--- a/aos/events/simulated_network_bridge.cc
+++ b/aos/events/simulated_network_bridge.cc
@@ -228,8 +228,8 @@
 
       // TODO(austin): Not cool.  We want to actually forward these.  This means
       // we need a more sophisticated concept of what is running.
-      // TODO(james): This fails if multiple messages are sent on the same channel
-      // within the same callback.
+      // TODO(james): This fails if multiple messages are sent on the same
+      // channel within the same callback.
       LOG(WARNING) << "Not forwarding message on "
                    << configuration::CleanedChannelToString(fetcher_->channel())
                    << " because we aren't running.  Set at "
diff --git a/aos/events/timing_report_dump.cc b/aos/events/timing_report_dump.cc
index 0e27b33..c71dcf5 100644
--- a/aos/events/timing_report_dump.cc
+++ b/aos/events/timing_report_dump.cc
@@ -1,9 +1,8 @@
-#include "aos/events/timing_report_dump_lib.h"
-
 #include "aos/configuration.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/timing_report_dump_lib.h"
 #include "aos/init.h"
 #include "aos/json_to_flatbuffer.h"
-#include "aos/events/logging/log_reader.h"
 #include "gflags/gflags.h"
 #include "glog/logging.h"
 
diff --git a/aos/events/timing_report_dump_lib.cc b/aos/events/timing_report_dump_lib.cc
index bd44ff6..b33cc73 100644
--- a/aos/events/timing_report_dump_lib.cc
+++ b/aos/events/timing_report_dump_lib.cc
@@ -21,8 +21,8 @@
   // width in the output stream).
   const auto num_width = std::setw(0);
   os << std::setfill(' ') << num_width << stats.average() << " [" << num_width
-     << stats.min() << ", " << num_width << stats.max() << "] std "
-     << num_width << stats.standard_deviation();
+     << stats.min() << ", " << num_width << stats.max() << "] std " << num_width
+     << stats.standard_deviation();
   return os;
 }
 
@@ -296,7 +296,7 @@
     }
   }
 }
-}
+}  // namespace
 
 void TimingReportDump::AccumulateReport(const timing::Report &raw_report) {
   CHECK(raw_report.has_pid());
@@ -370,7 +370,8 @@
 
 const Channel *TimingReportDump::GetChannel(int index) {
   CHECK_LT(0, index);
-  CHECK_GT(event_loop_->configuration()->channels()->size(), static_cast<size_t>(index));
+  CHECK_GT(event_loop_->configuration()->channels()->size(),
+           static_cast<size_t>(index));
   return event_loop_->configuration()->channels()->Get(index);
 }
 
diff --git a/aos/events/timing_report_dump_lib.h b/aos/events/timing_report_dump_lib.h
index a33bc3d..93163a1 100644
--- a/aos/events/timing_report_dump_lib.h
+++ b/aos/events/timing_report_dump_lib.h
@@ -1,7 +1,7 @@
 #ifndef AOS_EVENTS_TIMING_REPORT_DUMP_LIB_H_
 #define AOS_EVENTS_TIMING_REPORT_DUMP_LIB_H_
-#include <string>
 #include <map>
+#include <string>
 
 #include "aos/configuration.h"
 #include "aos/events/event_loop.h"
@@ -10,7 +10,6 @@
 #include "gflags/gflags.h"
 #include "glog/logging.h"
 
-
 namespace aos {
 // A class to handle printing timing report statistics in a useful format on the
 // command line. Main features:
@@ -32,9 +31,7 @@
 
   // Filter to use for application name. Currently requires that the provided
   // name exactly match the name of the application in question.
-  void ApplicationFilter(std::string_view name) {
-    name_filter_ = name;
-  }
+  void ApplicationFilter(std::string_view name) { name_filter_ = name; }
 
  private:
   void HandleTimingReport(const timing::Report &report);
@@ -62,7 +59,8 @@
   std::optional<std::string> name_filter_;
   // Key is pair of <process id, application name>, since neither is a unique
   // identifier across time.
-  std::map<std::pair<pid_t, std::string>, timing::ReportT> accumulated_statistics_;
+  std::map<std::pair<pid_t, std::string>, timing::ReportT>
+      accumulated_statistics_;
 };
 }  // namespace aos
 #endif  // AOS_EVENTS_TIMING_REPORT_DUMP_LIB_H_
diff --git a/aos/flatbuffer_merge_test.cc b/aos/flatbuffer_merge_test.cc
index 81aa2e1..89cecdb 100644
--- a/aos/flatbuffer_merge_test.cc
+++ b/aos/flatbuffer_merge_test.cc
@@ -3,11 +3,10 @@
 #include <string_view>
 
 #include "absl/strings/escaping.h"
-#include "gtest/gtest.h"
-
 #include "aos/json_to_flatbuffer.h"
 #include "aos/json_to_flatbuffer_generated.h"
 #include "flatbuffers/minireflect.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace testing {
diff --git a/aos/gtest_prod.h b/aos/gtest_prod.h
index 3050ae7..00859e2 100644
--- a/aos/gtest_prod.h
+++ b/aos/gtest_prod.h
@@ -28,9 +28,9 @@
 //   }  // namespace testing
 //   }  // namespace bla
 #define FORWARD_DECLARE_TEST_CASE(test_case_name, test_name) \
-    class test_case_name##_##test_name##_Test;
+  class test_case_name##_##test_name##_Test;
 #define FRIEND_TEST_NAMESPACE(test_case_name, test_name, namespace_name) \
-    friend class namespace_name::test_case_name##_##test_name##_Test
+  friend class namespace_name::test_case_name##_##test_name##_Test
 
 // Copied from googletest's gtest_prod.h. See that file for documentation.
 #define FRIEND_TEST(test_case_name, test_name) \
diff --git a/aos/ipc_lib/aos_sync.h b/aos/ipc_lib/aos_sync.h
index c5fede1..157c1b2 100644
--- a/aos/ipc_lib/aos_sync.h
+++ b/aos/ipc_lib/aos_sync.h
@@ -13,7 +13,8 @@
 
 // TODO(brians) add client requests to make helgrind useful with this code
 // <http://www.valgrind.org/docs/manual/hg-manual.html#hg-manual.client-requests>
-// and <http://www.valgrind.org/docs/manual/drd-manual.html#drd-manual.clientreqs>
+// and
+// <http://www.valgrind.org/docs/manual/drd-manual.html#drd-manual.clientreqs>
 // list the interesting ones
 
 // Have to remember to align structs containing it (recursively) to sizeof(int).
@@ -138,7 +139,7 @@
 int futex_wait(aos_futex *m) __attribute__((warn_unused_result));
 // The same as futex_wait except returns 2 if it times out.
 int futex_wait_timeout(aos_futex *m, const struct timespec *timeout)
-  __attribute__((warn_unused_result));
+    __attribute__((warn_unused_result));
 
 // Set the futex and wake up anybody waiting on it.
 // Returns the number that were woken or -1 with an error in errno.
diff --git a/aos/ipc_lib/eventfd_latency.cc b/aos/ipc_lib/eventfd_latency.cc
index d1f6bcb..0507f26 100644
--- a/aos/ipc_lib/eventfd_latency.cc
+++ b/aos/ipc_lib/eventfd_latency.cc
@@ -1,8 +1,7 @@
-#include "gflags/gflags.h"
-
 #include <sys/eventfd.h>
 #include <sys/stat.h>
 #include <sys/types.h>
+
 #include <chrono>
 #include <random>
 #include <thread>
@@ -14,6 +13,7 @@
 #include "aos/logging/logging.h"
 #include "aos/realtime.h"
 #include "aos/time/time.h"
+#include "gflags/gflags.h"
 
 // This is a demo program which uses named pipes to communicate.
 // It measures both latency of a random timer thread, and latency of the
diff --git a/aos/ipc_lib/futex_latency.cc b/aos/ipc_lib/futex_latency.cc
index 5761d40..1ec3fc1 100644
--- a/aos/ipc_lib/futex_latency.cc
+++ b/aos/ipc_lib/futex_latency.cc
@@ -1,8 +1,7 @@
-#include "gflags/gflags.h"
-
 #include <fcntl.h>
 #include <sys/stat.h>
 #include <sys/types.h>
+
 #include <chrono>
 #include <random>
 #include <thread>
@@ -15,6 +14,7 @@
 #include "aos/mutex/mutex.h"
 #include "aos/realtime.h"
 #include "aos/time/time.h"
+#include "gflags/gflags.h"
 
 DEFINE_int32(seconds, 10, "Duration of the test to run");
 DEFINE_int32(
diff --git a/aos/ipc_lib/index.cc b/aos/ipc_lib/index.cc
index ed58806..4701f51 100644
--- a/aos/ipc_lib/index.cc
+++ b/aos/ipc_lib/index.cc
@@ -1,7 +1,7 @@
 #include "aos/ipc_lib/index.h"
 
-#include <string>
 #include <sstream>
+#include <string>
 
 namespace aos {
 namespace ipc_lib {
diff --git a/aos/ipc_lib/index_test.cc b/aos/ipc_lib/index_test.cc
index 2e9a37b..a288ec9 100644
--- a/aos/ipc_lib/index_test.cc
+++ b/aos/ipc_lib/index_test.cc
@@ -1,7 +1,7 @@
 #include "aos/ipc_lib/index.h"
 
-#include "gtest/gtest.h"
 #include "glog/logging.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace ipc_lib {
diff --git a/aos/ipc_lib/latency_lib.h b/aos/ipc_lib/latency_lib.h
index 4d9b912..2371efa 100644
--- a/aos/ipc_lib/latency_lib.h
+++ b/aos/ipc_lib/latency_lib.h
@@ -4,6 +4,7 @@
 #include <fcntl.h>
 #include <sys/stat.h>
 #include <sys/types.h>
+
 #include <chrono>
 
 #include "aos/time/time.h"
diff --git a/aos/ipc_lib/lockless_queue_death_test.cc b/aos/ipc_lib/lockless_queue_death_test.cc
index c5edb9e..13eb1f5 100644
--- a/aos/ipc_lib/lockless_queue_death_test.cc
+++ b/aos/ipc_lib/lockless_queue_death_test.cc
@@ -618,8 +618,7 @@
       },
       [config, tid](void *raw_memory) {
         ::aos::ipc_lib::LocklessQueueMemory *const memory =
-            reinterpret_cast< ::aos::ipc_lib::LocklessQueueMemory *>(
-                raw_memory);
+            reinterpret_cast<::aos::ipc_lib::LocklessQueueMemory *>(raw_memory);
         // Confirm that we can create 2 senders (the number in the queue), and
         // send a message.  And that all the messages in the queue are valid.
         LocklessQueue queue(memory, memory, config);
diff --git a/aos/ipc_lib/lockless_queue_memory.h b/aos/ipc_lib/lockless_queue_memory.h
index bb995b9..b3f9468 100644
--- a/aos/ipc_lib/lockless_queue_memory.h
+++ b/aos/ipc_lib/lockless_queue_memory.h
@@ -2,6 +2,7 @@
 #define AOS_IPC_LIB_LOCKLESS_QUEUE_MEMORY_H_
 
 #include <sys/types.h>
+
 #include <cstddef>
 
 #include "aos/ipc_lib/aos_sync.h"
diff --git a/aos/ipc_lib/named_pipe_latency.cc b/aos/ipc_lib/named_pipe_latency.cc
index c333850..11ea66e 100644
--- a/aos/ipc_lib/named_pipe_latency.cc
+++ b/aos/ipc_lib/named_pipe_latency.cc
@@ -1,7 +1,6 @@
-#include "gflags/gflags.h"
-
 #include <sys/stat.h>
 #include <sys/types.h>
+
 #include <chrono>
 #include <random>
 #include <thread>
@@ -13,6 +12,7 @@
 #include "aos/logging/logging.h"
 #include "aos/realtime.h"
 #include "aos/time/time.h"
+#include "gflags/gflags.h"
 
 // This is a demo program which uses named pipes to communicate.
 // It measures both latency of a random timer thread, and latency of the
diff --git a/aos/ipc_lib/print_lockless_queue_memory.cc b/aos/ipc_lib/print_lockless_queue_memory.cc
index 6974d65..2cbcf12 100644
--- a/aos/ipc_lib/print_lockless_queue_memory.cc
+++ b/aos/ipc_lib/print_lockless_queue_memory.cc
@@ -1,10 +1,10 @@
-#include "aos/ipc_lib/lockless_queue.h"
-
 #include <fcntl.h>
 #include <sys/mman.h>
 #include <sys/stat.h>
 #include <sys/types.h>
 
+#include "aos/ipc_lib/lockless_queue.h"
+
 int main(int argc, char **argv) {
   CHECK_EQ(argc, 2);
   const char *path = argv[1];
diff --git a/aos/ipc_lib/shared_mem.h b/aos/ipc_lib/shared_mem.h
index edb9091..89a700e 100644
--- a/aos/ipc_lib/shared_mem.h
+++ b/aos/ipc_lib/shared_mem.h
@@ -2,8 +2,8 @@
 #define _SHARED_MEM_H_
 
 #include <stddef.h>
-#include <unistd.h>
 #include <time.h>
+#include <unistd.h>
 
 #include "aos/ipc_lib/shared_mem_types.h"
 
diff --git a/aos/ipc_lib/signalfd.h b/aos/ipc_lib/signalfd.h
index b3a9063..a6991de 100644
--- a/aos/ipc_lib/signalfd.h
+++ b/aos/ipc_lib/signalfd.h
@@ -3,6 +3,7 @@
 
 #include <sys/signalfd.h>
 #include <sys/types.h>
+
 #include <initializer_list>
 
 namespace aos {
diff --git a/aos/ipc_lib/signalfd_test.cc b/aos/ipc_lib/signalfd_test.cc
index a50e9f6..1c8e750 100644
--- a/aos/ipc_lib/signalfd_test.cc
+++ b/aos/ipc_lib/signalfd_test.cc
@@ -1,8 +1,8 @@
 #include "aos/ipc_lib/signalfd.h"
 
-#include "gtest/gtest.h"
-#include "glog/logging.h"
 #include "aos/testing/test_logging.h"
+#include "glog/logging.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace ipc_lib {
diff --git a/aos/json_tokenizer.cc b/aos/json_tokenizer.cc
index 9bb457c..0e235e6 100644
--- a/aos/json_tokenizer.cc
+++ b/aos/json_tokenizer.cc
@@ -378,7 +378,8 @@
               ConsumeWhitespace();
               state_ = State::kExpectObjectEnd;
             } else {
-              fprintf(stderr, "Error on line %d, expected } or ,\n", linenumber_);
+              fprintf(stderr, "Error on line %d, expected } or ,\n",
+                      linenumber_);
               return TokenType::kError;
             }
             break;
@@ -387,7 +388,8 @@
               ConsumeWhitespace();
               state_ = State::kExpectArrayEnd;
             } else {
-              fprintf(stderr, "Error on line %d, expected ] or ,\n", linenumber_);
+              fprintf(stderr, "Error on line %d, expected ] or ,\n",
+                      linenumber_);
               return TokenType::kError;
             }
             break;
diff --git a/aos/logging/dynamic_logging.cc b/aos/logging/dynamic_logging.cc
index d28fba2..1120a94 100644
--- a/aos/logging/dynamic_logging.cc
+++ b/aos/logging/dynamic_logging.cc
@@ -1,4 +1,5 @@
 #include "aos/logging/dynamic_logging.h"
+
 #include "glog/logging.h"
 
 namespace aos {
diff --git a/aos/logging/dynamic_logging.h b/aos/logging/dynamic_logging.h
index 9fd8fd0..7309bfc 100644
--- a/aos/logging/dynamic_logging.h
+++ b/aos/logging/dynamic_logging.h
@@ -1,6 +1,6 @@
 #include <string>
-#include "aos/events/event_loop.h"
 
+#include "aos/events/event_loop.h"
 #include "aos/logging/dynamic_log_command_generated.h"
 #include "glog/logging.h"
 
diff --git a/aos/logging/dynamic_logging_test.cc b/aos/logging/dynamic_logging_test.cc
index 216193c..e9cb475 100644
--- a/aos/logging/dynamic_logging_test.cc
+++ b/aos/logging/dynamic_logging_test.cc
@@ -1,8 +1,9 @@
+#include "aos/logging/dynamic_logging.h"
+
 #include <sys/stat.h>
 
 #include "aos/events/event_loop.h"
 #include "aos/events/simulated_event_loop.h"
-#include "aos/logging/dynamic_logging.h"
 #include "aos/testing/path.h"
 #include "glog/logging.h"
 #include "gtest/gtest.h"
diff --git a/aos/logging/logging.h b/aos/logging/logging.h
index c4a8e56..c71e5c4 100644
--- a/aos/logging/logging.h
+++ b/aos/logging/logging.h
@@ -174,7 +174,8 @@
 // base/logging.h provides its own #defines for the simpler names EQ, NE, etc.
 // This happens if, for example, those are used as token names in a
 // yacc grammar.
-AOS_DEFINE_CHECK_OP_IMPL(Check_EQ, ==)  // Compilation error with CHECK_EQ(NULL, x)?
+AOS_DEFINE_CHECK_OP_IMPL(Check_EQ,
+                         ==)  // Compilation error with CHECK_EQ(NULL, x)?
 AOS_DEFINE_CHECK_OP_IMPL(Check_NE, !=)  // Use CHECK(x == NULL) instead.
 AOS_DEFINE_CHECK_OP_IMPL(Check_LE, <=)
 AOS_DEFINE_CHECK_OP_IMPL(Check_LT, <)
diff --git a/aos/macros.h b/aos/macros.h
index 34010fb..c01aa81 100644
--- a/aos/macros.h
+++ b/aos/macros.h
@@ -6,8 +6,8 @@
 // A macro to disallow the copy constructor and operator= functions
 // This should be used in the private: declarations for a class
 #define DISALLOW_COPY_AND_ASSIGN(TypeName) \
-  TypeName(const TypeName&) = delete;      \
-  void operator=(const TypeName&) = delete
+  TypeName(const TypeName &) = delete;     \
+  void operator=(const TypeName &) = delete
 
 // A macro to wrap arguments to macros that contain commas.
 // Useful for DISALLOW_COPY_AND_ASSIGNing templated types with multiple template
@@ -18,7 +18,7 @@
 #define MACRO_DARG(...) (__VA_ARGS__)
 
 #ifdef __GNUC__
-#define UNUSED_VARIABLE __attribute__ ((unused))
+#define UNUSED_VARIABLE __attribute__((unused))
 #else
 #define UNUSED_VARIABLE
 #endif
diff --git a/aos/mutex/mutex.h b/aos/mutex/mutex.h
index a2af7ae..1a2a028 100644
--- a/aos/mutex/mutex.h
+++ b/aos/mutex/mutex.h
@@ -77,9 +77,7 @@
                  << " died but it shouldn't be able to";
     }
   }
-  ~MutexLocker() {
-    mutex_->Unlock();
-  }
+  ~MutexLocker() { mutex_->Unlock(); }
 
  private:
   Mutex *const mutex_;
diff --git a/aos/network/log_web_proxy_main.cc b/aos/network/log_web_proxy_main.cc
index 945d034..782c2be 100644
--- a/aos/network/log_web_proxy_main.cc
+++ b/aos/network/log_web_proxy_main.cc
@@ -1,7 +1,8 @@
 // Sample binary for running the web server code against a logfile.
 // This can be run by running
-// bazel run -c opt //aos/network:log_web_proxy_main -- --node node_to_replay /path/to/logfile
-// And then opening the plotting webpage at http://localhost:8080/graph.html
+// bazel run -c opt //aos/network:log_web_proxy_main -- --node node_to_replay
+// /path/to/logfile And then opening the plotting webpage at
+// http://localhost:8080/graph.html
 
 #include "aos/configuration.h"
 #include "aos/events/logging/log_reader.h"
diff --git a/aos/network/message_bridge_client.cc b/aos/network/message_bridge_client.cc
index 503ce95..8aad867 100644
--- a/aos/network/message_bridge_client.cc
+++ b/aos/network/message_bridge_client.cc
@@ -1,8 +1,7 @@
-#include "aos/network/message_bridge_client_lib.h"
-
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "aos/logging/dynamic_logging.h"
+#include "aos/network/message_bridge_client_lib.h"
 
 DEFINE_string(config, "aos_config.json", "Path to the config.");
 DEFINE_int32(rt_priority, -1, "If > 0, run as this RT priority");
diff --git a/aos/network/message_bridge_test.cc b/aos/network/message_bridge_test.cc
index d2a9b05..226daf7 100644
--- a/aos/network/message_bridge_test.cc
+++ b/aos/network/message_bridge_test.cc
@@ -457,8 +457,7 @@
       examples::Ping::Builder ping_builder =
           builder.MakeBuilder<examples::Ping>();
       ping_builder.add_value(ping_count + 971);
-      EXPECT_EQ(builder.Send(ping_builder.Finish()),
-                RawSender::Error::kOk);
+      EXPECT_EQ(builder.Send(ping_builder.Finish()), RawSender::Error::kOk);
       ++ping_count;
     }
   });
@@ -1323,7 +1322,6 @@
                   ->duplicate_packets(),
               1u);
 
-
     EXPECT_EQ(pi2_client_statistics_fetcher->connections()
                   ->Get(0)
                   ->partial_deliveries(),
diff --git a/aos/network/multinode_timestamp_filter.cc b/aos/network/multinode_timestamp_filter.cc
index 262cb5c..06cb526 100644
--- a/aos/network/multinode_timestamp_filter.cc
+++ b/aos/network/multinode_timestamp_filter.cc
@@ -82,22 +82,11 @@
     // another boot.  We wouldn't bother to build a problem to solve for
     // this node otherwise.  Confirm that is true so we at least get
     // notified if that assumption falls apart.
-    bool valid = false;
-    for (const struct FilterPair &other_filter :
-         clock_offset_filter_for_node_[filter.b_index]) {
-      if (other_filter.b_index == node_a) {
-        // Found our match.  Confirm it has timestamps.
-        if (other_filter.filter->timestamps_size(
-                base_clock_[filter.b_index].boot, base_clock_[node_a].boot) !=
-            0u) {
-          valid = true;
-        }
-        break;
-      }
-    }
-    if (!valid) {
+    if (filter.b_filter == nullptr) {
       return false;
     }
+    return (filter.b_filter->timestamps_size(base_clock_[filter.b_index].boot,
+                                             base_clock_[node_a].boot) != 0u);
   }
   return true;
 }
@@ -114,20 +103,9 @@
         // another boot.  We wouldn't bother to build a problem to solve for
         // this node otherwise.  Confirm that is true so we at least get
         // notified if that assumption falls apart.
-        bool valid = false;
-        for (const struct FilterPair &other_filter :
-             clock_offset_filter_for_node_[filter.b_index]) {
-          if (other_filter.b_index == i) {
-            // Found our match.  Confirm it has timestamps.
-            if (other_filter.filter->timestamps_size(
-                    base_clock_[filter.b_index].boot, base_clock_[i].boot) !=
-                0u) {
-              valid = true;
-            }
-            break;
-          }
-        }
-        if (!valid) {
+        if (filter.b_filter == nullptr ||
+            filter.b_filter->timestamps_size(base_clock_[filter.b_index].boot,
+                                             base_clock_[i].boot) == 0u) {
           Debug();
           LOG(FATAL) << "Found no timestamps in either direction between nodes "
                      << i << " and " << filter.b_index;
@@ -947,10 +925,10 @@
         configuration::GetNodeIndex(logged_configuration_, node_b);
 
     // TODO(austin): Do a better job documenting which node is which here.
-    filters_per_node_[node_a_index].emplace_back(x.GetFilter(node_a),
-                                                 node_b_index);
-    filters_per_node_[node_b_index].emplace_back(x.GetFilter(node_b),
-                                                 node_a_index);
+    filters_per_node_[node_a_index].emplace_back(
+        x.GetFilter(node_a), node_b_index, x.GetFilter(node_b));
+    filters_per_node_[node_b_index].emplace_back(
+        x.GetFilter(node_b), node_a_index, x.GetFilter(node_a));
     return &x;
   } else {
     return &it->second;
@@ -1302,7 +1280,7 @@
           all_live_nodes.Set(node_a_index, true);
           all_live_nodes.Set(filter.b_index, true);
           problem.add_clock_offset_filter(node_a_index, filter.filter,
-                                          filter.b_index);
+                                          filter.b_index, filter.b_filter);
 
           if (timestamp_mappers_[node_a_index] != nullptr) {
             // Now, we have cases at startup where we have a couple of points
diff --git a/aos/network/multinode_timestamp_filter.h b/aos/network/multinode_timestamp_filter.h
index f959d7b..77d5226 100644
--- a/aos/network/multinode_timestamp_filter.h
+++ b/aos/network/multinode_timestamp_filter.h
@@ -47,8 +47,10 @@
   //   filter[a_index]->Offset(ta) + ta => t(b_index);
   void add_clock_offset_filter(size_t a_index,
                                const NoncausalTimestampFilter *filter,
-                               size_t b_index) {
-    clock_offset_filter_for_node_[a_index].emplace_back(filter, b_index);
+                               size_t b_index,
+                               const NoncausalTimestampFilter *b_filter) {
+    clock_offset_filter_for_node_[a_index].emplace_back(filter, b_index,
+                                                        b_filter);
   }
 
   // Solves the optimization problem phrased using the symmetric Netwon's method
@@ -138,10 +140,13 @@
   // Filter and the node index it is referencing.
   //   filter->Offset(ta) + ta => t_(b_node);
   struct FilterPair {
-    FilterPair(const NoncausalTimestampFilter *my_filter, size_t my_b_index)
-        : filter(my_filter), b_index(my_b_index) {}
+    FilterPair(const NoncausalTimestampFilter *my_filter, size_t my_b_index,
+               const NoncausalTimestampFilter *b_filter)
+        : filter(my_filter), b_index(my_b_index), b_filter(b_filter) {}
     const NoncausalTimestampFilter *const filter;
     const size_t b_index;
+
+    const NoncausalTimestampFilter *const b_filter;
   };
 
   // List of filters indexed by node.
@@ -394,10 +399,12 @@
   // Filter and the node index it is referencing.
   //   filter->Offset(ta) + ta => t_(b_node);
   struct FilterPair {
-    FilterPair(NoncausalTimestampFilter *my_filter, size_t my_b_index)
-        : filter(my_filter), b_index(my_b_index) {}
+    FilterPair(NoncausalTimestampFilter *my_filter, size_t my_b_index,
+               NoncausalTimestampFilter *b_filter)
+        : filter(my_filter), b_index(my_b_index), b_filter(b_filter) {}
     NoncausalTimestampFilter *const filter;
     const size_t b_index;
+    NoncausalTimestampFilter *const b_filter;
   };
   std::vector<std::vector<FilterPair>> filters_per_node_;
 
diff --git a/aos/network/multinode_timestamp_filter_test.cc b/aos/network/multinode_timestamp_filter_test.cc
index c2a3b71..e1a4cd6 100644
--- a/aos/network/multinode_timestamp_filter_test.cc
+++ b/aos/network/multinode_timestamp_filter_test.cc
@@ -1,12 +1,12 @@
-#include "aos/network/timestamp_filter.h"
+#include "aos/network/multinode_timestamp_filter.h"
 
 #include <chrono>
 
 #include "aos/configuration.h"
 #include "aos/json_to_flatbuffer.h"
 #include "aos/macros.h"
-#include "aos/network/multinode_timestamp_filter.h"
 #include "aos/network/testing_time_converter.h"
+#include "aos/network/timestamp_filter.h"
 #include "gtest/gtest.h"
 
 namespace aos {
@@ -189,7 +189,7 @@
   const BootTimestamp me = BootTimestamp::epoch();
   const BootTimestamp me2{.boot = 1u, .time = monotonic_clock::epoch()};
 
-  //LOG(FATAL) << "TODO(austin): Test ToDistributedClock too";
+  // LOG(FATAL) << "TODO(austin): Test ToDistributedClock too";
 
   TestingTimeConverter time_converter(3u);
   size_t reboot_counter = 0;
@@ -361,8 +361,8 @@
   TimestampProblem problem(2);
   problem.set_base_clock(0, ta);
   problem.set_base_clock(1, e);
-  problem.add_clock_offset_filter(0, &a, 1);
-  problem.add_clock_offset_filter(1, &b, 0);
+  problem.add_clock_offset_filter(0, &a, 1, &b);
+  problem.add_clock_offset_filter(1, &b, 0, &a);
 
   problem.Debug();
 
diff --git a/aos/network/sctp_lib_test.cc b/aos/network/sctp_lib_test.cc
index ed3c15e..53b285f 100644
--- a/aos/network/sctp_lib_test.cc
+++ b/aos/network/sctp_lib_test.cc
@@ -1,4 +1,5 @@
 #include "aos/network/sctp_lib.h"
+
 #include "aos/init.h"
 #include "gflags/gflags.h"
 
diff --git a/aos/network/timestamp_filter_test.cc b/aos/network/timestamp_filter_test.cc
index a5a4b98..07ea682 100644
--- a/aos/network/timestamp_filter_test.cc
+++ b/aos/network/timestamp_filter_test.cc
@@ -692,14 +692,11 @@
     ASSERT_EQ(filter.timestamps_size(), 2u);
     filter.FreezeUntil(tb, {0, monotonic_clock::min_time});
 
-    EXPECT_DEATH(
-        {
-          filter.Sample(tb, oa);
-        },
-        "monotonic_now > frozen_time_ \\(0.100000000sec vs. "
-        "0.100000000sec\\) : test_a -> test_b Tried to insert "
-        "0.100000000sec before the frozen time of 0.100000000sec.  "
-        "Increase --time_estimation_buffer_seconds to greater than 0");
+    EXPECT_DEATH({ filter.Sample(tb, oa); },
+                 "monotonic_now > frozen_time_ \\(0.100000000sec vs. "
+                 "0.100000000sec\\) : test_a -> test_b Tried to insert "
+                 "0.100000000sec before the frozen time of 0.100000000sec.  "
+                 "Increase --time_estimation_buffer_seconds to greater than 0");
   }
 
   {
@@ -712,9 +709,7 @@
     filter.FreezeUntil(tc, {0, monotonic_clock::min_time});
 
     EXPECT_DEATH(
-        {
-          filter.Sample(tc, oc);
-        },
+        { filter.Sample(tc, oc); },
         "test_a -> test_b Returned a horizontal line previously and then got a "
         "new sample at "
         "0.200000000sec, 0.2 seconds after the last sample at 0.000000000sec");
@@ -730,9 +725,7 @@
     filter.FreezeUntil(tc, {0, monotonic_clock::min_time});
 
     EXPECT_DEATH(
-        {
-          filter.Sample(tb, ob);
-        },
+        { filter.Sample(tb, ob); },
         "monotonic_now > frozen_time_ \\(0.100000000sec vs. "
         "0.200000000sec\\) : test_a -> test_b Tried to insert "
         "0.100000000sec before the frozen time of 0.200000000sec.  "
@@ -1041,9 +1034,10 @@
 
   EXPECT_EQ(filter.Offset(t1, 0.0, 0), std::make_pair(o1, 0.0));
 
-  EXPECT_EQ(filter.Offset(
-                e + (t2.time_since_epoch() + t1.time_since_epoch()) / 2, 0.0, 0),
-            std::make_pair(o1, (o2d - o1d) / 2.));
+  EXPECT_EQ(
+      filter.Offset(e + (t2.time_since_epoch() + t1.time_since_epoch()) / 2,
+                    0.0, 0),
+      std::make_pair(o1, (o2d - o1d) / 2.));
 
   EXPECT_EQ(filter.Offset(t2, 0.0, 0), std::make_pair(o2, 0.0));
 
diff --git a/aos/network/web_proxy.cc b/aos/network/web_proxy.cc
index 30707b2..7161ee3 100644
--- a/aos/network/web_proxy.cc
+++ b/aos/network/web_proxy.cc
@@ -208,7 +208,6 @@
     return;
   }
 
-
   while (fetcher_->FetchNext()) {
     // If we aren't building up a buffer, short-circuit the FetchNext().
     if (buffer_size_ == 0) {
@@ -304,7 +303,8 @@
       });
 }
 
-void Subscriber::RemoveListener(std::shared_ptr<ScopedDataChannel> data_channel) {
+void Subscriber::RemoveListener(
+    std::shared_ptr<ScopedDataChannel> data_channel) {
   channels_.erase(
       std::remove_if(
           channels_.begin(), channels_.end(),
@@ -636,8 +636,7 @@
         CHECK(data_channel) << ": Subscriber got destroyed before we started.";
         // Raw pointer inside the subscriber so we don't have a circular
         // reference.  AddListener will close it.
-        subscribers_[channel_index]->AddListener(data_channel,
-                                                 transfer_method);
+        subscribers_[channel_index]->AddListener(data_channel, transfer_method);
       });
 
       Subscriber *subscriber = subscribers_[channel_index].get();
diff --git a/aos/network/web_proxy_utils.h b/aos/network/web_proxy_utils.h
index 19b496d..de64329 100644
--- a/aos/network/web_proxy_utils.h
+++ b/aos/network/web_proxy_utils.h
@@ -1,7 +1,7 @@
 #include "absl/types/span.h"
-#include "aos/network/web_proxy_generated.h"
 #include "aos/events/event_loop.h"
 #include "aos/flatbuffers.h"
+#include "aos/network/web_proxy_generated.h"
 
 namespace aos {
 namespace web_proxy {
diff --git a/aos/realtime.cc b/aos/realtime.cc
index f8ab639..ef98671 100644
--- a/aos/realtime.cc
+++ b/aos/realtime.cc
@@ -287,7 +287,6 @@
 
 void *malloc(size_t size) __attribute__((weak, alias("aos_malloc_hook")));
 void free(void *ptr) __attribute__((weak, alias("aos_free_hook")));
-
 }
 
 void RegisterMallocHook() {
diff --git a/aos/starter/starter_test.cc b/aos/starter/starter_test.cc
index 06f961a..87cb544 100644
--- a/aos/starter/starter_test.cc
+++ b/aos/starter/starter_test.cc
@@ -437,7 +437,6 @@
     }
   });
 
-
   SetupStarterCleanup(&starter);
 
   std::thread starterd_thread([&starter] { starter.Run(); });
diff --git a/aos/starter/subprocess_test.cc b/aos/starter/subprocess_test.cc
index 93fbf6a..71f701a 100644
--- a/aos/starter/subprocess_test.cc
+++ b/aos/starter/subprocess_test.cc
@@ -44,7 +44,10 @@
   aos::TimerHandler *exit_timer =
       event_loop.AddTimer([&event_loop]() { event_loop.Exit(); });
   event_loop.OnRun([&event_loop, exit_timer]() {
-    exit_timer->Setup(event_loop.monotonic_now() + std::chrono::seconds(1));
+    // Note: we are using the backup poll in this test to capture SIGCHLD.  This
+    // runs at 1 hz, so make sure we let it run at least once.
+    exit_timer->Setup(event_loop.monotonic_now() +
+                      std::chrono::milliseconds(1500));
   });
 
   event_loop.Run();
@@ -83,8 +86,10 @@
   echo_stderr.set_capture_stderr(true);
 
   echo_stderr.Start();
+  // Note: we are using the backup poll in this test to capture SIGCHLD.  This
+  // runs at 1 hz, so make sure we let it run at least once.
   event_loop.AddTimer([&event_loop]() { event_loop.Exit(); })
-      ->Setup(event_loop.monotonic_now() + std::chrono::seconds(1));
+      ->Setup(event_loop.monotonic_now() + std::chrono::milliseconds(1500));
 
   event_loop.Run();
 
diff --git a/aos/stl_mutex/stl_mutex_test.cc b/aos/stl_mutex/stl_mutex_test.cc
index 5e88c56..5abd934 100644
--- a/aos/stl_mutex/stl_mutex_test.cc
+++ b/aos/stl_mutex/stl_mutex_test.cc
@@ -1,8 +1,7 @@
 #include "aos/stl_mutex/stl_mutex.h"
 
-#include "gtest/gtest.h"
-
 #include "aos/die.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace testing {
diff --git a/aos/testing/gtest_main.cc b/aos/testing/gtest_main.cc
index c8e3172..a6e944c 100644
--- a/aos/testing/gtest_main.cc
+++ b/aos/testing/gtest_main.cc
@@ -1,6 +1,7 @@
-#include <iostream>
 #include <getopt.h>
 
+#include <iostream>
+
 #include "aos/init.h"
 #include "gflags/gflags.h"
 #include "glog/logging.h"
@@ -17,7 +18,7 @@
 namespace testing {
 
 // Actually declared/defined in //aos/testing:test_logging.
-void SetLogFileName(const char* filename) __attribute__((weak));
+void SetLogFileName(const char *filename) __attribute__((weak));
 void ForcePrintLogsDuringTests() __attribute__((weak));
 
 }  // namespace testing
diff --git a/aos/testing/path.cc b/aos/testing/path.cc
index f999e58..f63fd97 100644
--- a/aos/testing/path.cc
+++ b/aos/testing/path.cc
@@ -1,4 +1,5 @@
 #include "aos/testing/path.h"
+
 #include "absl/strings/str_cat.h"
 
 namespace aos {
diff --git a/aos/testing/path.h b/aos/testing/path.h
index 1abad74..7f4187d 100644
--- a/aos/testing/path.h
+++ b/aos/testing/path.h
@@ -7,7 +7,7 @@
 namespace aos {
 namespace testing {
 
-// Returns the path to the provided artifact which works 
+// Returns the path to the provided artifact which works
 std::string ArtifactPath(std::string_view path);
 
 }  // namespace testing
diff --git a/aos/testing/test_logging.h b/aos/testing/test_logging.h
index 0a26b07..5e01879 100644
--- a/aos/testing/test_logging.h
+++ b/aos/testing/test_logging.h
@@ -15,7 +15,7 @@
 
 // Redirect the messages enabled by EnableTestLogging() function to a file.
 // By default the messages are printed to standard output.
-void SetLogFileName(const char* filename);
+void SetLogFileName(const char *filename);
 
 // Force the messages to be printed as they are handled by the logging
 // framework. This can be useful for tests that hang where no messages would
diff --git a/aos/testing/test_logging_test.cc b/aos/testing/test_logging_test.cc
index f39c6cf..e7f9806 100644
--- a/aos/testing/test_logging_test.cc
+++ b/aos/testing/test_logging_test.cc
@@ -2,9 +2,8 @@
 
 #include <thread>
 
-#include "gtest/gtest.h"
-
 #include "aos/logging/logging.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace testing {
diff --git a/aos/time/time_test.cc b/aos/time/time_test.cc
index 38e389a..4fbf821 100644
--- a/aos/time/time_test.cc
+++ b/aos/time/time_test.cc
@@ -2,11 +2,10 @@
 
 #include <thread>
 
-#include "gtest/gtest.h"
-#include "glog/logging.h"
-
 #include "aos/macros.h"
 #include "aos/util/death_test_log_implementation.h"
+#include "glog/logging.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace time {
diff --git a/aos/unique_malloc_ptr.h b/aos/unique_malloc_ptr.h
index eb92f11..ddc41aa 100644
--- a/aos/unique_malloc_ptr.h
+++ b/aos/unique_malloc_ptr.h
@@ -9,18 +9,18 @@
 
 // Written as a functor so that it doesn't have to get passed to
 // std::unique_ptr's constructor as an argument.
-template<typename T, void(*function)(T *)>
+template <typename T, void (*function)(T *)>
 class const_wrap {
  public:
-  void operator()(const T *ptr) {
-    function(const_cast<T *>(ptr));
-  }
+  void operator()(const T *ptr) { function(const_cast<T *>(ptr)); }
 };
 
 // Wrapper function to deal with the differences between C and C++ (C++ doesn't
 // automatically convert T* to void* like C).
-template<typename T>
-void free_type(T *ptr) { ::free(reinterpret_cast<void *>(ptr)); }
+template <typename T>
+void free_type(T *ptr) {
+  ::free(reinterpret_cast<void *>(ptr));
+}
 
 }  // namespace internal
 
@@ -35,11 +35,11 @@
 
   // perfect forwarding of these 2 to make unique_ptr work
   template <typename... Args>
-  unique_c_ptr(Args &&... args)
+  unique_c_ptr(Args &&...args)
       : std::unique_ptr<T, internal::const_wrap<T, function>>(
             std::forward<Args>(args)...) {}
-  template<typename... Args>
-  unique_c_ptr<T, function> &operator=(Args&&... args) {
+  template <typename... Args>
+  unique_c_ptr<T, function> &operator=(Args &&...args) {
     std::unique_ptr<T, internal::const_wrap<T, function>>::operator=(
         std::forward<Args>(args)...);
     return *this;
diff --git a/aos/util/generate_test_log.cc b/aos/util/generate_test_log.cc
index 7338af8..12cc260 100644
--- a/aos/util/generate_test_log.cc
+++ b/aos/util/generate_test_log.cc
@@ -1,13 +1,14 @@
 #include "aos/configuration.h"
 #include "aos/events/logging/log_writer.h"
-#include "aos/init.h"
-#include "aos/json_to_flatbuffer.h"
-#include "gflags/gflags.h"
-#include "aos/testing/path.h"
 #include "aos/events/ping_lib.h"
 #include "aos/events/pong_lib.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/testing/path.h"
+#include "gflags/gflags.h"
 
-DEFINE_string(output_folder, "", "Name of folder to write the generated logfile to.");
+DEFINE_string(output_folder, "",
+              "Name of folder to write the generated logfile to.");
 
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
diff --git a/aos/util/global_factory.h b/aos/util/global_factory.h
index 5e47972..2a4028e 100644
--- a/aos/util/global_factory.h
+++ b/aos/util/global_factory.h
@@ -67,7 +67,7 @@
   class SubClassRegisterer {
    public:
     explicit SubClassRegisterer(const char *name) {
-      (*GetMap())[name] = [](FactoryArgs &&... args) {
+      (*GetMap())[name] = [](FactoryArgs &&...args) {
         return std::unique_ptr<BaseClass>(
             new SubClass(std::forward<FactoryArgs>(args)...));
       };
diff --git a/aos/util/global_factory_test.cc b/aos/util/global_factory_test.cc
index d50e931..da386b2 100644
--- a/aos/util/global_factory_test.cc
+++ b/aos/util/global_factory_test.cc
@@ -1,4 +1,5 @@
 #include "aos/util/global_factory.h"
+
 #include "gtest/gtest.h"
 
 namespace aos {
diff --git a/aos/util/log_interval.h b/aos/util/log_interval.h
index b6410a9..d346852 100644
--- a/aos/util/log_interval.h
+++ b/aos/util/log_interval.h
@@ -1,11 +1,11 @@
 #ifndef AOS_UTIL_LOG_INTERVAL_H_
 #define AOS_UTIL_LOG_INTERVAL_H_
 
+#include <string>
+
 #include "aos/logging/logging.h"
 #include "aos/time/time.h"
 
-#include <string>
-
 namespace aos {
 namespace util {
 
diff --git a/aos/util/mcap_logger_test.cc b/aos/util/mcap_logger_test.cc
index 6e82a53..8bc3419 100644
--- a/aos/util/mcap_logger_test.cc
+++ b/aos/util/mcap_logger_test.cc
@@ -1,6 +1,7 @@
 #include "aos/util/mcap_logger.h"
 
 #include <iostream>
+
 #include "flatbuffers/reflection_generated.h"
 #include "gtest/gtest.h"
 
diff --git a/aos/util/options.h b/aos/util/options.h
index 39f7e8f..f393030 100644
--- a/aos/util/options.h
+++ b/aos/util/options.h
@@ -87,6 +87,6 @@
   friend class Option;
 };
 
-}  // namespace options
+}  // namespace aos
 
 #endif  // AOS_UTIL_OPTIONS_H_
diff --git a/aos/util/phased_loop.h b/aos/util/phased_loop.h
index c9e4933..307b400 100644
--- a/aos/util/phased_loop.h
+++ b/aos/util/phased_loop.h
@@ -41,8 +41,8 @@
   // Returns the number of iterations which have passed (1 if this is called
   // often enough). This can be < 1 iff monotonic_now goes backwards between
   // calls.
-  int Iterate(const monotonic_clock::time_point monotonic_now =
-                  monotonic_clock::now());
+  int Iterate(
+      const monotonic_clock::time_point monotonic_now = monotonic_clock::now());
 
   // Sleeps until the next time and returns the number of iterations which have
   // passed.
diff --git a/aos/util/phased_loop_test.cc b/aos/util/phased_loop_test.cc
index 96eeb5c..5e85ea0 100644
--- a/aos/util/phased_loop_test.cc
+++ b/aos/util/phased_loop_test.cc
@@ -1,8 +1,7 @@
 #include "aos/util/phased_loop.h"
 
-#include "gtest/gtest.h"
-
 #include "aos/time/time.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace time {
diff --git a/aos/util/scoped_pipe.cc b/aos/util/scoped_pipe.cc
index d677b07..e2e0ca5 100644
--- a/aos/util/scoped_pipe.cc
+++ b/aos/util/scoped_pipe.cc
@@ -1,6 +1,7 @@
 #include "aos/util/scoped_pipe.h"
 
 #include <fcntl.h>
+
 #include "glog/logging.h"
 
 namespace aos::util {
diff --git a/aos/util/top.cc b/aos/util/top.cc
index 22d67c8..9a6bbd0 100644
--- a/aos/util/top.cc
+++ b/aos/util/top.cc
@@ -153,7 +153,7 @@
   std::set<pid_t> pids = pids_to_track_;
   // Ensure that we check on the status of every process that we are already
   // tracking.
-  for (const auto & reading : readings_) {
+  for (const auto &reading : readings_) {
     pids.insert(reading.first);
   }
   if (track_all_) {
diff --git a/aos/util/top_test.cc b/aos/util/top_test.cc
index 36afd64..3292927 100644
--- a/aos/util/top_test.cc
+++ b/aos/util/top_test.cc
@@ -28,7 +28,8 @@
         event_loop_(&config_.message()) {
     FLAGS_shm_base = shm_dir_;
 
-    // Nuke the shm dir, to ensure we aren't being affected by any preexisting tests.
+    // Nuke the shm dir, to ensure we aren't being affected by any preexisting
+    // tests.
     aos::util::UnlinkRecursive(shm_dir_);
   }
   ~TopTest() {
diff --git a/aos/util/trapezoid_profile.h b/aos/util/trapezoid_profile.h
index 944c423..c5c957b 100644
--- a/aos/util/trapezoid_profile.h
+++ b/aos/util/trapezoid_profile.h
@@ -2,7 +2,6 @@
 #define AOS_UTIL_TRAPEZOID_PROFILE_H_
 
 #include "Eigen/Dense"
-
 #include "aos/macros.h"
 #include "aos/time/time.h"
 
diff --git a/aos/util/trapezoid_profile_test.cc b/aos/util/trapezoid_profile_test.cc
index 79795e1..afd64ea 100644
--- a/aos/util/trapezoid_profile_test.cc
+++ b/aos/util/trapezoid_profile_test.cc
@@ -1,8 +1,7 @@
-#include "gtest/gtest.h"
+#include "aos/util/trapezoid_profile.h"
 
 #include "Eigen/Dense"
-
-#include "aos/util/trapezoid_profile.h"
+#include "gtest/gtest.h"
 
 namespace aos {
 namespace util {
@@ -20,10 +19,8 @@
   }
 
   // Runs an iteration.
-  void RunIteration(double goal_position,
-                    double goal_velocity) {
-    position_ = profile_.Update(goal_position,
-                                goal_velocity);
+  void RunIteration(double goal_position, double goal_velocity) {
+    position_ = profile_.Update(goal_position, goal_velocity);
   }
 
   const Eigen::Matrix<double, 2, 1> &position() { return position_; }
@@ -33,15 +30,15 @@
   ::testing::AssertionResult At(double position, double velocity) {
     static const double kDoubleNear = 0.00001;
     if (::std::abs(velocity - position_(1)) > kDoubleNear) {
-      return ::testing::AssertionFailure() << "velocity is " << position_(1) <<
-          " not " << velocity;
+      return ::testing::AssertionFailure()
+             << "velocity is " << position_(1) << " not " << velocity;
     }
     if (::std::abs(position - position_(0)) > kDoubleNear) {
-      return ::testing::AssertionFailure() << "position is " << position_(0) <<
-          " not " << position;
+      return ::testing::AssertionFailure()
+             << "position is " << position_(0) << " not " << position;
     }
-    return ::testing::AssertionSuccess() << "at " << position <<
-        " moving at " << velocity;
+    return ::testing::AssertionSuccess()
+           << "at " << position << " moving at " << velocity;
   }
 
  private:
diff --git a/aos/uuid.cc b/aos/uuid.cc
index 2e3290b..86baed6 100644
--- a/aos/uuid.cc
+++ b/aos/uuid.cc
@@ -3,6 +3,7 @@
 #include <fcntl.h>
 #include <sys/stat.h>
 #include <sys/types.h>
+
 #include <array>
 #include <random>
 #include <string_view>
diff --git a/aos/vision/blob/codec_test.cc b/aos/vision/blob/codec_test.cc
index 53dc3bb..d510e58 100644
--- a/aos/vision/blob/codec_test.cc
+++ b/aos/vision/blob/codec_test.cc
@@ -1,6 +1,7 @@
 #include "aos/vision/blob/codec.h"
 
 #include <algorithm>
+
 #include "gtest/gtest.h"
 
 namespace aos {
diff --git a/aos/vision/blob/range_image.h b/aos/vision/blob/range_image.h
index a735442..d962788 100644
--- a/aos/vision/blob/range_image.h
+++ b/aos/vision/blob/range_image.h
@@ -38,8 +38,12 @@
   RangeImage() {}
 
   bool operator==(const RangeImage &other) const {
-    if (min_y_ != other.min_y_) { return false; }
-    if (ranges_ != other.ranges_) { return false; }
+    if (min_y_ != other.min_y_) {
+      return false;
+    }
+    if (ranges_ != other.ranges_) {
+      return false;
+    }
     return true;
   }
   bool operator!=(const RangeImage &other) const { return !(*this == other); }
diff --git a/aos/vision/blob/stream_view.h b/aos/vision/blob/stream_view.h
index 4cee7b4..0db69e5 100644
--- a/aos/vision/blob/stream_view.h
+++ b/aos/vision/blob/stream_view.h
@@ -1,12 +1,12 @@
 #ifndef _AOS_VISION_BLOB_STREAM_VIEW_H_
 #define _AOS_VISION_BLOB_STREAM_VIEW_H_
 
+#include <memory>
+
 #include "aos/vision/blob/range_image.h"
 #include "aos/vision/debug/debug_window.h"
 #include "aos/vision/image/image_types.h"
 
-#include <memory>
-
 namespace aos {
 namespace vision {
 
diff --git a/aos/vision/blob/threshold.cc b/aos/vision/blob/threshold.cc
index 047d8db..c4f8a9e 100644
--- a/aos/vision/blob/threshold.cc
+++ b/aos/vision/blob/threshold.cc
@@ -29,14 +29,16 @@
     for (int x = 0; x < fmt.w / kChunkSize; ++x) {
       // The per-channel (YUYV) values in the current chunk.
       uint8_t chunk_channels[2 * kChunkSize];
-      memcpy(&chunk_channels[0], current_row + x * kChunkSize * 2, 2 * kChunkSize);
+      memcpy(&chunk_channels[0], current_row + x * kChunkSize * 2,
+             2 * kChunkSize);
       __builtin_prefetch(current_row + (x + 1) * kChunkSize * 2);
 
       for (int i = 0; i < kChunkSize; ++i) {
         if ((chunk_channels[i * 2] > value) != in_range) {
           const int here = x * kChunkSize + i;
           if (in_range) {
-            current_row_ranges.emplace_back(ImageRange(current_range_start, here));
+            current_row_ranges.emplace_back(
+                ImageRange(current_range_start, here));
           } else {
             current_range_start = here;
           }
diff --git a/aos/vision/blob/transpose_test.cc b/aos/vision/blob/transpose_test.cc
index a5c2964..374b5bf 100644
--- a/aos/vision/blob/transpose_test.cc
+++ b/aos/vision/blob/transpose_test.cc
@@ -1,8 +1,9 @@
 #include "aos/vision/blob/transpose.h"
-#include "aos/vision/blob/test_utils.h"
 
 #include <algorithm>
 #include <string>
+
+#include "aos/vision/blob/test_utils.h"
 #include "gtest/gtest.h"
 
 namespace aos {
diff --git a/aos/vision/debug/aveugle-source.cc b/aos/vision/debug/aveugle-source.cc
index d03be14..65a8e84 100644
--- a/aos/vision/debug/aveugle-source.cc
+++ b/aos/vision/debug/aveugle-source.cc
@@ -1,9 +1,9 @@
-#include "aos/vision/debug/debug_framework.h"
-
 #include <gdk/gdk.h>
+
 #include <fstream>
 #include <string>
 
+#include "aos/vision/debug/debug_framework.h"
 #include "aos/vision/image/camera_params.pb.h"
 #include "aos/vision/image/image_stream.h"
 
@@ -46,9 +46,8 @@
           ++i_;
         }
       });
-      interface_->InstallSetExposure([this](int abs_exp) {
-          this->SetExposure(abs_exp);
-      });
+      interface_->InstallSetExposure(
+          [this](int abs_exp) { this->SetExposure(abs_exp); });
     }
     void ProcessImage(DataRef data, aos::monotonic_clock::time_point) override {
       prev_data_ = std::string(data);
diff --git a/aos/vision/debug/blob_log-source.cc b/aos/vision/debug/blob_log-source.cc
index 26706bb..006c09a 100644
--- a/aos/vision/debug/blob_log-source.cc
+++ b/aos/vision/debug/blob_log-source.cc
@@ -1,17 +1,16 @@
-#include "aos/vision/debug/debug_framework.h"
-
 #include <gdk/gdk.h>
 #include <gtk/gtk.h>
 #include <sys/stat.h>
 #include <unistd.h>
+
 #include <fstream>
 #include <functional>
 #include <string>
 
 #include "aos/vision/blob/codec.h"
 #include "aos/vision/blob/stream_view.h"
+#include "aos/vision/debug/debug_framework.h"
 #include "aos/vision/debug/overlay.h"
-
 #include "glog/logging.h"
 
 namespace aos {
diff --git a/aos/vision/debug/camera-source.cc b/aos/vision/debug/camera-source.cc
index 5eeabfc..578ebc1 100644
--- a/aos/vision/debug/camera-source.cc
+++ b/aos/vision/debug/camera-source.cc
@@ -1,9 +1,9 @@
-#include "aos/vision/debug/debug_framework.h"
-
 #include <gdk/gdk.h>
+
 #include <fstream>
 #include <string>
 
+#include "aos/vision/debug/debug_framework.h"
 #include "aos/vision/image/camera_params.pb.h"
 #include "aos/vision/image/image_stream.h"
 
diff --git a/aos/vision/debug/debug_framework.h b/aos/vision/debug/debug_framework.h
index d8ed4a1..c2913c2 100644
--- a/aos/vision/debug/debug_framework.h
+++ b/aos/vision/debug/debug_framework.h
@@ -44,9 +44,8 @@
   void InstallSetExposure(std::function<void(int)> set_exp) {
     set_exposure_ = set_exp;
   }
-  void SetExposure(int abs_exp) {
-    set_exposure_(abs_exp);
-  }
+  void SetExposure(int abs_exp) { set_exposure_(abs_exp); }
+
  private:
   std::function<void(int)> set_exposure_;
 };
diff --git a/aos/vision/debug/debug_window.h b/aos/vision/debug/debug_window.h
index aa31a8c..573cef5 100644
--- a/aos/vision/debug/debug_window.h
+++ b/aos/vision/debug/debug_window.h
@@ -2,7 +2,9 @@
 #define AOS_VISION_DEBUG_DEBUG_WINDOW_H_
 
 #include <cairo.h>
+
 #include <functional>
+
 #include "aos/vision/debug/overlay.h"
 #include "aos/vision/image/image_types.h"
 
diff --git a/aos/vision/debug/jpeg_list-source.cc b/aos/vision/debug/jpeg_list-source.cc
index 027acc9..ecc3f14 100644
--- a/aos/vision/debug/jpeg_list-source.cc
+++ b/aos/vision/debug/jpeg_list-source.cc
@@ -1,11 +1,11 @@
-#include "aos/vision/debug/debug_framework.h"
-
-#include "aos/vision/image/image_dataset.h"
-
 #include <gdk/gdk.h>
+
 #include <fstream>
 #include <string>
 
+#include "aos/vision/debug/debug_framework.h"
+#include "aos/vision/image/image_dataset.h"
+
 namespace aos {
 namespace vision {
 
@@ -37,16 +37,15 @@
       interface_->NewJpeg(frame.data);
     } else {
       const auto &data = frame.data;
-      interface_->NewImage({640, 480},
-                           [&](ImagePtr img_data) {
-                             for (int y = 0; y < 480; ++y) {
-                               for (int x = 0; x < 640; ++x) {
-                                 uint8_t v = data[y * 640 * 2 + x * 2 + 0];
-                                 img_data.get_px(x, y) = PixelRef{v, v, v};
-                               }
-                             }
-                             return false;
-                           });
+      interface_->NewImage({640, 480}, [&](ImagePtr img_data) {
+        for (int y = 0; y < 480; ++y) {
+          for (int x = 0; x < 640; ++x) {
+            uint8_t v = data[y * 640 * 2 + x * 2 + 0];
+            img_data.get_px(x, y) = PixelRef{v, v, v};
+          }
+        }
+        return false;
+      });
     }
   }
 
diff --git a/aos/vision/debug/overlay.h b/aos/vision/debug/overlay.h
index c668e17..a2cecd5 100644
--- a/aos/vision/debug/overlay.h
+++ b/aos/vision/debug/overlay.h
@@ -239,7 +239,7 @@
   std::vector<std::pair<Vector<2>, double>> circles_;
 };
 
-}  // vision
-}  // aos
+}  // namespace vision
+}  // namespace aos
 
 #endif  // _AOS_VISION_IMAGE_DEBUG_OVERLAY_H_
diff --git a/aos/vision/debug/tcp-source.cc b/aos/vision/debug/tcp-source.cc
index b95e189..de406ae 100644
--- a/aos/vision/debug/tcp-source.cc
+++ b/aos/vision/debug/tcp-source.cc
@@ -1,15 +1,15 @@
-#include "aos/vision/debug/debug_framework.h"
-
 #include <gdk/gdk.h>
 #include <gtk/gtk.h>
 #include <sys/stat.h>
 #include <unistd.h>
+
 #include <cstdlib>
 #include <fstream>
 #include <functional>
 #include <string>
 
 #include "aos/vision/blob/codec.h"
+#include "aos/vision/debug/debug_framework.h"
 #include "aos/vision/events/tcp_client.h"
 
 namespace aos {
diff --git a/aos/vision/events/gtk_event.cc b/aos/vision/events/gtk_event.cc
index d1f60a1..e1e4e08 100644
--- a/aos/vision/events/gtk_event.cc
+++ b/aos/vision/events/gtk_event.cc
@@ -1,12 +1,13 @@
 #include <gdk/gdk.h>
 #include <gtk/gtk.h>
 #include <sys/epoll.h>
+
 #include <condition_variable>
 #include <mutex>
 #include <thread>
 
-#include "aos/vision/events/epoll_events.h"
 #include "aos/logging/logging.h"
+#include "aos/vision/events/epoll_events.h"
 
 namespace aos {
 namespace events {
diff --git a/aos/vision/events/tcp_client.h b/aos/vision/events/tcp_client.h
index 74f1418..8aab2cc 100644
--- a/aos/vision/events/tcp_client.h
+++ b/aos/vision/events/tcp_client.h
@@ -1,11 +1,11 @@
 #ifndef _AOS_VISION_DEBUG_TCP_CLIENT_H_
 #define _AOS_VISION_DEBUG_TCP_CLIENT_H_
 
-#include "aos/vision/events/epoll_events.h"
-
 #include <memory>
 #include <string>
 
+#include "aos/vision/events/epoll_events.h"
+
 namespace aos {
 namespace events {
 
diff --git a/aos/vision/events/tcp_server.h b/aos/vision/events/tcp_server.h
index 3116f55..24b4f60 100644
--- a/aos/vision/events/tcp_server.h
+++ b/aos/vision/events/tcp_server.h
@@ -1,12 +1,12 @@
 #ifndef _AOS_VISION_EVENTS_TCP_SERVER_H_
 #define _AOS_VISION_EVENTS_TCP_SERVER_H_
 
-#include "aos/vision/events/epoll_events.h"
-#include "aos/vision/events/intrusive_free_list.h"
-
 #include <memory>
 #include <vector>
 
+#include "aos/vision/events/epoll_events.h"
+#include "aos/vision/events/intrusive_free_list.h"
+
 namespace aos {
 namespace events {
 
diff --git a/aos/vision/image/V4L2.h b/aos/vision/image/V4L2.h
index d02229a..ed93606 100644
--- a/aos/vision/image/V4L2.h
+++ b/aos/vision/image/V4L2.h
@@ -4,10 +4,9 @@
 // This file handles including everything needed to use V4L2 and has some
 // utility functions.
 
-#include <sys/ioctl.h>
-
 #include <asm/types.h> /* for videodev2.h */
 #include <linux/videodev2.h>
+#include <sys/ioctl.h>
 
 namespace camera {
 
diff --git a/aos/vision/image/image_stream.h b/aos/vision/image/image_stream.h
index 5d88d32..60e71b2 100644
--- a/aos/vision/image/image_stream.h
+++ b/aos/vision/image/image_stream.h
@@ -1,12 +1,12 @@
 #ifndef AOS_VISION_IMAGE_IMAGE_STREAM_H_
 #define AOS_VISION_IMAGE_IMAGE_STREAM_H_
 
+#include <memory>
+
 #include "aos/vision/events/epoll_events.h"
 #include "aos/vision/image/camera_params.pb.h"
 #include "aos/vision/image/reader.h"
 
-#include <memory>
-
 namespace aos {
 namespace vision {
 
diff --git a/aos/vision/image/image_types.h b/aos/vision/image/image_types.h
index 0238841..ee56f7d 100644
--- a/aos/vision/image/image_types.h
+++ b/aos/vision/image/image_types.h
@@ -2,8 +2,8 @@
 #define _AOS_VISION_IMAGE_IMAGE_TYPES_H_
 
 #include <cstdint>
-#include <limits>
 #include <cstring>
+#include <limits>
 #include <memory>
 #include <sstream>
 #include <string_view>
diff --git a/motors/pistol_grip/drivers_station.cc b/motors/pistol_grip/drivers_station.cc
index 4ed641c..eaa4486 100644
--- a/motors/pistol_grip/drivers_station.cc
+++ b/motors/pistol_grip/drivers_station.cc
@@ -263,7 +263,7 @@
   PORTC_PCR5 = PORT_PCR_DSE | PORT_PCR_MUX(1);
 
   // Set up the CAN pins.
-#if 0
+#if 1
   // Pistol grip motor controller board.
   PORTA_PCR12 = PORT_PCR_DSE | PORT_PCR_MUX(2);
   PORTA_PCR13 = PORT_PCR_DSE | PORT_PCR_MUX(2);
diff --git a/tools/bazel b/tools/bazel
index edb1aca..72ca2f8 100755
--- a/tools/bazel
+++ b/tools/bazel
@@ -24,7 +24,7 @@
   exec "${BAZEL_OVERRIDE}" "$@"
 fi
 
-readonly VERSION="5.0.0"
+readonly VERSION="5.1.1"
 
 readonly DOWNLOAD_DIR="${HOME}/.cache/bazel"
 # Directory to unpack bazel into.  This must change whenever bazel changes.
diff --git a/y2022/actors/autonomous_actor.cc b/y2022/actors/autonomous_actor.cc
index 4f49f81..e4e3f9d 100644
--- a/y2022/actors/autonomous_actor.cc
+++ b/y2022/actors/autonomous_actor.cc
@@ -13,9 +13,9 @@
 #include "y2022/control_loops/drivetrain/drivetrain_base.h"
 
 DEFINE_bool(spline_auto, false, "If true, define a spline autonomous mode");
-DEFINE_bool(rapid_react, false,
+DEFINE_bool(rapid_react, true,
             "If true, run the main rapid react autonomous mode");
-DEFINE_bool(rapid_react_two, true,
+DEFINE_bool(rapid_react_two, false,
             "If true, run the two ball rapid react autonomous mode");
 
 namespace y2022 {
@@ -240,14 +240,15 @@
   if (!splines[0].WaitForPlan()) return;
   splines[0].Start();
   // Distance before we don't shoot while moving.
-  if (!splines[0].WaitForSplineDistanceRemaining(0.25)) return;
+  if (!splines[0].WaitForSplineDistanceRemaining(2.1)) return;
+  LOG(INFO) << "Tring to take the shot";
 
   set_fire_at_will(true);
   SendSuperstructureGoal();
 
   if (!splines[0].WaitForSplineDistanceRemaining(0.02)) return;
 
-  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+  std::this_thread::sleep_for(std::chrono::milliseconds(500));
 
   // Fire the last ball we picked up when stopped.
   SendSuperstructureGoal();
@@ -295,14 +296,15 @@
   set_fire_at_will(true);
   SendSuperstructureGoal();
   if (!WaitForBallsShot()) return;
-  set_fire_at_will(false);
-  SendSuperstructureGoal();
 
   LOG(INFO) << "Took "
             << chrono::duration<double>(aos::monotonic_clock::now() -
                                         start_time)
                    .count()
             << 's';
+  std::this_thread::sleep_for(std::chrono::milliseconds(500));
+  set_fire_at_will(false);
+  SendSuperstructureGoal();
 }
 
 // Rapid React Two Ball Autonomous.
diff --git a/y2022/actors/splines/spline_5_ball_1.json b/y2022/actors/splines/spline_5_ball_1.json
index 46fddbb..714a32f 100644
--- a/y2022/actors/splines/spline_5_ball_1.json
+++ b/y2022/actors/splines/spline_5_ball_1.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [0.009329753853116074, -0.014583556392633312, 1.086141950245409, 1.3463506181539948, 1.8252560302734366, 2.7940085985321357], "spline_y": [2.2499321755598816, 3.695204931543886, 3.9907963594941256, 3.2671894020316525, 2.3428532547468994, 2.267936657588998], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.5}, {"constraint_type": "VOLTAGE", "value": 12.0}, {"constraint_type": "VELOCITY", "value": 0.5, "start_distance": 1.0, "end_distance": 1.20}, {"constraint_type": "VELOCITY", "value": 1.0, "start_distance": 2.8, "end_distance": 10}]}
+{"spline_count": 2, "spline_x": [0.009329753853116074, -0.014583556392633312, 0.422898189882277, 1.4291000715422806, 1.097942601889267, 1.2200715559987714, 1.3422005101082757, 1.9176158879802978, 1.9126144508213603, 2.390982044198304, 2.828066666162801], "spline_y": [2.2499321755598816, 3.695204931543886, 3.66990682978292, 3.865039154335479, 2.817866440962664, 2.191432999504318, 1.5649995580459715, 1.3593053885020936, 2.1916687001689623, 2.017440733036113, 2.150368378568702], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 3.0}, {"constraint_type": "VOLTAGE", "value": 12.0}, {"constraint_type": "VELOCITY", "value": 0.7, "start_distance": 1.0, "end_distance": 1.2}, {"constraint_type": "VELOCITY", "value": 0.65, "start_distance": 3.2, "end_distance": 3.3}]}
\ No newline at end of file
diff --git a/y2022/actors/splines/spline_5_ball_2.json b/y2022/actors/splines/spline_5_ball_2.json
index 3ccf4d4..bcbe879 100644
--- a/y2022/actors/splines/spline_5_ball_2.json
+++ b/y2022/actors/splines/spline_5_ball_2.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [2.8029000394337356, 3.598701010385372, 3.592928864987311, 5.716241105891047, 6.058409698241228, 6.836921351984797], "spline_y": [2.2659592486204163, 2.2235586475607194, 1.3732945972518653, 1.187231336623733, 1.965522252857657, 2.7153394202517944], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 3.0}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [2.837423982549179, 3.6088159516600333, 3.5883680571264422, 5.716241105891047, 6.058409698241228, 6.836921351984797], "spline_y": [2.1368542190716946, 2.3917438640763313, 1.516301392456306, 1.187231336623733, 1.965522252857657, 2.7153394202517944], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 3.0}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2022/constants.cc b/y2022/constants.cc
index 3fbe27b..37b43a1 100644
--- a/y2022/constants.cc
+++ b/y2022/constants.cc
@@ -216,26 +216,32 @@
     case kCompTeamNumber:
       climber->potentiometer_offset = -0.0463847608752 - 0.0376876182111 +
                                       0.0629263851579 - 0.00682128836400001 +
-                                      0.0172237531191 - 0.0172237531191;
+                                      0.0172237531191 - 0.0172237531191 +
+                                      0.00443383743660001 - 0.0117667224279;
 
       intake_front->potentiometer_offset =
-          2.79628370453323 - 0.0250288114832881 + 0.577152542437606 + 0.476513825677792;
+          2.79628370453323 - 0.0250288114832881 + 0.577152542437606 +
+          0.476513825677792 - 0.47869991531664 + 0.50529913945481 -
+          0.796768714398522 + 0.163696825540674 - 0.0963353449092312;
       intake_front->subsystem_params.zeroing_constants
-          .measured_absolute_position = 0.205422145836751;
+          .measured_absolute_position = 0.175014091275898;
 
       intake_back->potentiometer_offset =
           3.1409576474047 + 0.278653334013286 + 0.00879137908308503 +
-          0.0837134053818833 + 0.832945730100298 - 0.00759895654985426 - 2.03114758819475;
+          0.0837134053818833 + 0.832945730100298 - 0.00759895654985426 -
+          2.03114758819475 + 0.318379597392509 + 0.675664531140745 +
+          0.0650864893911517;
       intake_back->subsystem_params.zeroing_constants
-          .measured_absolute_position = 0.352050723370449;
+          .measured_absolute_position = 0.0517274215962501;
 
       turret->potentiometer_offset =
           -9.99970387166721 + 0.06415943 + 0.073290115367682 -
           0.0634440443622909 + 0.213601224728352 + 0.0657973101027296 -
           0.114726411377978 - 0.980314029089968 - 0.0266013159299456 +
-          0.0631240002215899 + 0.222882504808653;
+          0.0631240002215899 + 0.222882504808653 + 0.0370686419434252 -
+          0.0965027214840068 - 0.126737479717192;
       turret->subsystem_params.zeroing_constants.measured_absolute_position =
-          1.14081767944401;
+          1.3081068967929;
 
       flipper_arm_left->potentiometer_offset = -6.4;
       flipper_arm_right->potentiometer_offset = 5.56;
diff --git a/y2022/control_loops/superstructure/turret/aiming.cc b/y2022/control_loops/superstructure/turret/aiming.cc
index 6320cb7..c570856 100644
--- a/y2022/control_loops/superstructure/turret/aiming.cc
+++ b/y2022/control_loops/superstructure/turret/aiming.cc
@@ -18,7 +18,7 @@
 constexpr double kTurretZeroOffset = M_PI;
 
 constexpr double kMaxProfiledVelocity = 10.0;
-constexpr double kMaxProfiledAccel = 20.0;
+constexpr double kMaxProfiledAccel = 25.0;
 
 flatbuffers::DetachedBuffer MakePrefilledGoal() {
   flatbuffers::FlatBufferBuilder fbb;
diff --git a/y2022/joystick_reader.cc b/y2022/joystick_reader.cc
index 26c7f33..59d495a 100644
--- a/y2022/joystick_reader.cc
+++ b/y2022/joystick_reader.cc
@@ -308,7 +308,7 @@
       if (turret_pos.has_value()) {
         turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
             *builder.fbb(), turret_pos.value(),
-            CreateProfileParameters(*builder.fbb(), 10.0, 20.0));
+            CreateProfileParameters(*builder.fbb(), 10.0, 25.0));
       }
 
       flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
diff --git a/y2022/vision/camera_reader_main.cc b/y2022/vision/camera_reader_main.cc
index bfd1c7d..9a01679 100644
--- a/y2022/vision/camera_reader_main.cc
+++ b/y2022/vision/camera_reader_main.cc
@@ -10,7 +10,7 @@
 DEFINE_double(duty_cycle, 0.65, "Duty cycle of the LEDs");
 DEFINE_uint32(exposure, 5,
               "Exposure time, in 100us increments; 0 implies auto exposure");
-DEFINE_uint32(outdoors_exposure, 4,
+DEFINE_uint32(outdoors_exposure, 13,
               "Exposure time when using --use_outdoors, in 100us increments; 0 "
               "implies auto exposure");