Merge "Increase spline UI screen size"
diff --git a/aos/containers/BUILD b/aos/containers/BUILD
index 70d98f1..e9f8262 100644
--- a/aos/containers/BUILD
+++ b/aos/containers/BUILD
@@ -17,6 +17,7 @@
     deps = [
         ":ring_buffer",
         "//aos/testing:googletest",
+        "@com_github_google_glog//:glog",
     ],
 )
 
diff --git a/aos/containers/ring_buffer.h b/aos/containers/ring_buffer.h
index cd7872e..b928354 100644
--- a/aos/containers/ring_buffer.h
+++ b/aos/containers/ring_buffer.h
@@ -10,23 +10,116 @@
 // will start overwriting the oldest data.
 template <typename Data, size_t buffer_size>
 class RingBuffer {
+  template <typename ValueType, typename BufferType>
+  struct generic_iterator {
+    using iterator_category = ::std::random_access_iterator_tag;
+    using value_type = ValueType;
+    using difference_type = ::std::ptrdiff_t;
+    using pointer = value_type *;
+    using reference = value_type &;
+
+    explicit generic_iterator(BufferType *buffer, size_t index)
+        : buffer_(buffer), index_(index) {}
+
+    generic_iterator &operator++() {
+      ++index_;
+      return *this;
+    }
+    generic_iterator operator++(int) {
+      const generic_iterator retval = *this;
+      ++(*this);
+      return retval;
+    }
+    generic_iterator &operator--() {
+      --index_;
+      return *this;
+    }
+    generic_iterator operator--(int) {
+      const generic_iterator retval = *this;
+      --(*this);
+      return retval;
+    }
+
+    generic_iterator &operator+=(ptrdiff_t i) {
+      index_ += i;
+      return *this;
+    }
+    generic_iterator operator+(ptrdiff_t i) const {
+      generic_iterator retval = *this;
+      retval += i;
+      return retval;
+    }
+    generic_iterator &operator-=(ptrdiff_t i) {
+      index_ -= i;
+      return *this;
+    }
+    generic_iterator operator-(ptrdiff_t i) const {
+      generic_iterator retval = *this;
+      retval -= i;
+      return retval;
+    }
+
+    ptrdiff_t operator-(generic_iterator other) const {
+      return index_ - other.index_;
+    }
+
+    bool operator==(generic_iterator other) const {
+      return buffer_ == other.buffer_ && index_ == other.index_;
+    }
+    bool operator!=(generic_iterator other) const { return !(*this == other); }
+
+    bool operator<(generic_iterator other) const {
+      return buffer_ == other.buffer_ && index_ < other.index_;
+    }
+    bool operator>(generic_iterator other) const {
+      return buffer_ == other.buffer_ && index_ > other.index_;
+    }
+    bool operator<=(generic_iterator other) const {
+      return buffer_ == other.buffer_ && index_ <= other.index_;
+    }
+    bool operator>=(generic_iterator other) const {
+      return buffer_ == other.buffer_ && index_ >= other.index_;
+    }
+
+    reference operator*() const { return (*buffer_)[index_]; }
+    pointer operator->() const { return &(*buffer_)[index_]; }
+
+    reference operator[](difference_type i) const {
+      return (*buffer_)[index_ + i];
+    }
+
+   private:
+    BufferType *buffer_;
+    size_t index_;
+  };
+
  public:
+  using iterator = generic_iterator<Data, RingBuffer>;
+  using const_iterator = generic_iterator<const Data, const RingBuffer>;
+
   static constexpr size_t kBufferSize = buffer_size;
 
   constexpr RingBuffer() {}
+  ~RingBuffer() { Reset(); }
 
-  // Add an item to the RingBuffer, overwriting the oldest element if necessary
-  void Push(const Data &data) {
+  // Add an item to the RingBuffer, overwriting the oldest element if necessary.
+  //
+  // Invalidates the end iterator.
+  void Push(Data data) {
     if (full()) {
-      data_[oldest_] = data;
+      (*this)[0] = std::move(data);
       oldest_ = (oldest_ + 1) % buffer_size;
     } else {
-      data_[(oldest_ + size_) % buffer_size] = data;
+      new (&(*this)[size_]) Data(std::move(data));
       ++size_;
     }
   }
 
+  // Removes the oldest element.
+  //
+  // Invalidates all iterators.
   void Shift() {
+    (*this)[0].~Data();
     oldest_ = (oldest_ + 1) % buffer_size;
     --size_;
   }
@@ -34,11 +127,24 @@
   // Return the value of the index requested, adjusted so that the RingBuffer
   // contains the oldest element first and the newest last.
   Data &operator[](size_t index) {
-    return data_[(oldest_ + index) % buffer_size];
+#if defined(__cpp_lib_launder) && __cpp_lib_launder >= 201606
+    return *std::launder(
+        reinterpret_cast<Data *>(&data_[(oldest_ + index) % buffer_size]));
+#else
+    // TODO(brian): Remove this when all our compilers are 17 or newer.
+    return *reinterpret_cast<Data *>(&data_[(oldest_ + index) % buffer_size]);
+#endif
   }
 
   const Data &operator[](size_t index) const {
-    return data_[(oldest_ + index) % buffer_size];
+#if defined(__cpp_lib_launder) && __cpp_lib_launder >= 201606
+    return *std::launder(reinterpret_cast<const Data *>(
+        &data_[(oldest_ + index) % buffer_size]));
+#else
+    // TODO(brian): Remove this when all our compilers are 17 or newer.
+    return *reinterpret_cast<const Data *>(
+        &data_[(oldest_ + index) % buffer_size]);
+#endif
   }
 
   // Returns the capacity of the RingBuffer
@@ -53,69 +159,13 @@
   bool full() const { return size_ == buffer_size; }
 
   // Clears all the data out of the buffer.
-  void Reset() { size_ = 0; }
-
-  class iterator {
-   public:
-    using iterator_category = ::std::forward_iterator_tag;
-    using value_type = Data;
-    using difference_type = ::std::ptrdiff_t;
-    using pointer = Data *;
-    using reference = Data &;
-
-    explicit iterator(RingBuffer *buffer, size_t index)
-        : buffer_(buffer), index_(index) {}
-
-    iterator &operator++() {
-      ++index_;
-      return *this;
+  //
+  // Invalidates all iterators.
+  void Reset() {
+    while (!empty()) {
+      Shift();
     }
-    iterator operator++(int) {
-      iterator retval = *this;
-      ++(*this);
-      return retval;
-    }
-    bool operator==(iterator other) const {
-      return buffer_ == other.buffer_ && index_ == other.index_;
-    }
-    bool operator!=(iterator other) const { return !(*this == other); }
-    reference operator*() const { return (*buffer_)[index_]; }
-
-   private:
-    RingBuffer *buffer_;
-    size_t index_;
-  };
-
-  class const_iterator {
-   public:
-    using iterator_category = ::std::forward_iterator_tag;
-    using value_type = Data;
-    using difference_type = ::std::ptrdiff_t;
-    using pointer = Data *;
-    using reference = Data &;
-
-    explicit const_iterator(const RingBuffer *buffer, size_t index)
-        : buffer_(buffer), index_(index) {}
-
-    const_iterator &operator++() {
-      ++index_;
-      return *this;
-    }
-    const_iterator operator++(int) {
-      const_iterator retval = *this;
-      ++(*this);
-      return retval;
-    }
-    bool operator==(const_iterator other) const {
-      return buffer_ == other.buffer_ && index_ == other.index_;
-    }
-    bool operator!=(const_iterator other) const { return !(*this == other); }
-    const Data &operator*() const { return (*buffer_)[index_]; }
-
-   private:
-    const RingBuffer *buffer_;
-    size_t index_;
-  };
+  }
 
   iterator begin() { return iterator(this, 0); }
   iterator end() { return iterator(this, size()); }
@@ -124,10 +174,12 @@
   const_iterator end() const { return const_iterator(this, size()); }
 
  private:
-  ::std::array<Data, buffer_size> data_;
+  using DataStorage =
+      typename std::aligned_storage<sizeof(Data), alignof(Data)>::type;
+  std::array<DataStorage, buffer_size> data_;
 
-  // Oldest contains the oldest item added to the RingBuffer which will be the
-  // next one to be overwritten
+  // Oldest contains the oldest item added to the RingBuffer which will be
+  // the next one to be overwritten
   size_t oldest_ = 0;
   size_t size_ = 0;
 };
diff --git a/aos/containers/ring_buffer_test.cc b/aos/containers/ring_buffer_test.cc
index 01e057f..b4cf1fb 100644
--- a/aos/containers/ring_buffer_test.cc
+++ b/aos/containers/ring_buffer_test.cc
@@ -1,16 +1,70 @@
 #include "aos/containers/ring_buffer.h"
 
+#include "glog/logging.h"
 #include "gtest/gtest.h"
 
 namespace aos {
 namespace testing {
 
+// A class which is implicitly convertible to and from int, and tracks object
+// lifetimes.
+struct TrackedInt {
+  enum class State { kNoValue, kAlive, kDestroyed };
+
+  static int instance_count;
+  int value;
+  State state;
+
+  TrackedInt(int new_value) : value(new_value), state(State::kAlive) {
+    ++instance_count;
+  }
+
+  TrackedInt(const TrackedInt &other) = delete;
+  TrackedInt(TrackedInt &&other) : value(other.value), state(other.state) {
+    CHECK(other.state != State::kDestroyed);
+    other.state = State::kNoValue;
+    ++instance_count;
+  }
+  ~TrackedInt() {
+    CHECK(state != State::kDestroyed);
+    state = State::kDestroyed;
+    --instance_count;
+    CHECK_GE(instance_count, 0);
+  }
+  TrackedInt &operator=(const TrackedInt &other) = delete;
+  TrackedInt &operator=(TrackedInt &&other) {
+    CHECK(state != State::kDestroyed);
+    CHECK(other.state != State::kDestroyed);
+    state = other.state;
+    other.state = State::kNoValue;
+    value = other.value;
+    return *this;
+  }
+
+  operator int() const {
+    CHECK(state == State::kAlive);
+    return value;
+  }
+};
+
+int TrackedInt::instance_count;
+
+struct TrackedIntTracker {
+  TrackedIntTracker() {
+    CHECK_EQ(0, TrackedInt::instance_count) << ": Instances alive before test";
+  }
+  ~TrackedIntTracker() {
+    CHECK_EQ(0, TrackedInt::instance_count) << ": Instances alive after test";
+  }
+};
+
 class RingBufferTest : public ::testing::Test {
  public:
   RingBufferTest() {}
 
  protected:
-  RingBuffer<int, 10> buffer_;
+  TrackedIntTracker tracked_int_tracker_;
+  RingBuffer<TrackedInt, 10> buffer_;
 };
 
 // Test if the RingBuffer is empty when initialized properly
@@ -37,9 +91,8 @@
     buffer_.Push(i);
 
     // The buffer shouldn't be empty and it's size should be 1 more since we
-    // just
-    // added an item. Also, the last item in the buffer should equal the one we
-    // just added
+    // just added an item. Also, the last item in the buffer should equal the
+    // one we just added
     ASSERT_FALSE(buffer_.empty());
     ASSERT_EQ(i + 1, buffer_.size());
     ASSERT_EQ(i, buffer_[i]);
@@ -60,8 +113,7 @@
   ASSERT_TRUE(buffer_.full());
 
   // Since the buffer is a size of 10 and has been filled up 2.5 times, it
-  // should
-  // now contain the numbers 15-24
+  // should now contain the numbers 15-24
   for (size_t i = 0; i < buffer_.size(); ++i) {
     ASSERT_EQ(15 + i, buffer_[i]);
   }
@@ -144,7 +196,7 @@
     buffer_.Push(i);
   }
 
-  const RingBuffer<int, 10> &cbuffer = buffer_;
+  const RingBuffer<TrackedInt, 10> &cbuffer = buffer_;
 
   int i = 0;
   for (const int element : cbuffer) {
diff --git a/aos/events/logging/log_edit.cc b/aos/events/logging/log_edit.cc
index 7eff9e7..78d5eff 100644
--- a/aos/events/logging/log_edit.cc
+++ b/aos/events/logging/log_edit.cc
@@ -42,7 +42,7 @@
 
     aos::logger::DetachedBufferWriter buffer_writer(
         FLAGS_logfile, std::make_unique<aos::logger::DummyEncoder>());
-    buffer_writer.QueueSizedFlatbuffer(&fbb);
+    buffer_writer.QueueSizedFlatbuffer(&fbb, aos::monotonic_clock::min_time);
 
     while (true) {
       absl::Span<const uint8_t> msg_data = span_reader.ReadMessage();
diff --git a/aos/events/logging/log_namer.cc b/aos/events/logging/log_namer.cc
index a0625d0..6cf91db 100644
--- a/aos/events/logging/log_namer.cc
+++ b/aos/events/logging/log_namer.cc
@@ -87,7 +87,10 @@
 MultiNodeLogNamer::MultiNodeLogNamer(std::string_view base_name,
                                      const Configuration *configuration,
                                      const Node *node)
-    : LogNamer(node), base_name_(base_name), configuration_(configuration) {}
+    : LogNamer(node),
+      base_name_(base_name),
+      old_base_name_(),
+      configuration_(configuration) {}
 
 MultiNodeLogNamer::~MultiNodeLogNamer() {
   if (!ran_out_of_space_) {
@@ -334,6 +337,12 @@
     // Refuse to open any new files, which might skip data. Any existing files
     // are in the same folder, which means they're on the same filesystem, which
     // means they're probably going to run out of space and get stuck too.
+    if (!destination->get()) {
+      // But avoid leaving a nullptr writer if we're out of space when
+      // attempting to open the first file.
+      *destination = std::make_unique<DetachedBufferWriter>(
+          DetachedBufferWriter::already_out_of_space_t());
+    }
     return;
   }
   const std::string_view separator = base_name_.back() == '/' ? "" : "_";
@@ -370,11 +379,28 @@
   if (temp_suffix_.empty()) {
     return;
   }
-  const std::string current_filename = std::string(destination->filename());
+  std::string current_filename = std::string(destination->filename());
   CHECK(current_filename.size() > temp_suffix_.size());
-  const std::string final_filename =
+  std::string final_filename =
       current_filename.substr(0, current_filename.size() - temp_suffix_.size());
-  const int result = rename(current_filename.c_str(), final_filename.c_str());
+  int result = rename(current_filename.c_str(), final_filename.c_str());
+
+  // When changing the base name, we rename the log folder while there active
+  // buffer writers. Therefore, the name of that active buffer may still refer
+  // to the old file location rather than the new one. This minimized changes to
+  // existing code.
+  if (result != 0 && errno != ENOSPC && !old_base_name_.empty()) {
+    auto offset = current_filename.find(old_base_name_);
+    if (offset != std::string::npos) {
+      current_filename.replace(offset, old_base_name_.length(), base_name_);
+    }
+    offset = final_filename.find(old_base_name_);
+    if (offset != std::string::npos) {
+      final_filename.replace(offset, old_base_name_.length(), base_name_);
+    }
+    result = rename(current_filename.c_str(), final_filename.c_str());
+  }
+
   if (result != 0) {
     if (errno == ENOSPC) {
       ran_out_of_space_ = true;
@@ -383,6 +409,8 @@
       PLOG(FATAL) << "Renaming " << current_filename << " to " << final_filename
                   << " failed";
     }
+  } else {
+    VLOG(1) << "Renamed " << current_filename << " -> " << final_filename;
   }
 }
 
diff --git a/aos/events/logging/log_namer.h b/aos/events/logging/log_namer.h
index 8f3f712..3b2c83c 100644
--- a/aos/events/logging/log_namer.h
+++ b/aos/events/logging/log_namer.h
@@ -23,6 +23,15 @@
   LogNamer(const Node *node) : node_(node) { nodes_.emplace_back(node_); }
   virtual ~LogNamer() {}
 
+  virtual std::string_view base_name() const = 0;
+
+  // Rotate should be called at least once in between calls to set_base_name.
+  // Otherwise temporary files will not be recoverable.
+  // Rotate is called by Logger::RenameLogBase, which is currently the only user
+  // of this method.
+  // Only renaming the folder is supported, not the file base name.
+  virtual void set_base_name(std::string_view base_name) = 0;
+
   // Writes the header to all log files for a specific node.  This function
   // needs to be called after all the writers are created.
   //
@@ -101,6 +110,12 @@
         data_writer_(OpenDataWriter()) {}
   ~LocalLogNamer() override = default;
 
+  std::string_view base_name() const final { return base_name_; }
+
+  void set_base_name(std::string_view base_name) final {
+    base_name_ = base_name;
+  }
+
   void WriteHeader(
       aos::SizePrefixedFlatbufferDetachedBuffer<LogFileHeader> *header,
       const Node *node) override;
@@ -132,7 +147,7 @@
         std::make_unique<aos::logger::DummyEncoder>());
   }
 
-  const std::string base_name_;
+  std::string base_name_;
   const UUID uuid_;
   size_t part_number_ = 0;
   std::unique_ptr<DetachedBufferWriter> data_writer_;
@@ -145,7 +160,12 @@
                     const Configuration *configuration, const Node *node);
   ~MultiNodeLogNamer() override;
 
-  std::string_view base_name() const { return base_name_; }
+  std::string_view base_name() const final { return base_name_; }
+
+  void set_base_name(std::string_view base_name) final {
+    old_base_name_ = base_name_;
+    base_name_ = base_name;
+  }
 
   // If temp_suffix is set, then this will write files under names beginning
   // with the specified suffix, and then rename them to the desired name after
@@ -344,7 +364,8 @@
     return t;
   }
 
-  const std::string base_name_;
+  std::string base_name_;
+  std::string old_base_name_;
   const Configuration *const configuration_;
 
   bool ran_out_of_space_ = false;
diff --git a/aos/events/logging/log_writer.cc b/aos/events/logging/log_writer.cc
index f68bbf6..6630441 100644
--- a/aos/events/logging/log_writer.cc
+++ b/aos/events/logging/log_writer.cc
@@ -1,5 +1,7 @@
 #include "aos/events/logging/log_writer.h"
 
+#include <dirent.h>
+
 #include <functional>
 #include <map>
 #include <vector>
@@ -14,6 +16,7 @@
 namespace logger {
 namespace {
 using message_bridge::RemoteMessage;
+namespace chrono = std::chrono;
 }  // namespace
 
 Logger::Logger(EventLoop *event_loop, const Configuration *configuration,
@@ -22,7 +25,7 @@
       configuration_(configuration),
       name_(network::GetHostname()),
       timer_handler_(event_loop_->AddTimer(
-          [this]() { DoLogData(event_loop_->monotonic_now()); })),
+          [this]() { DoLogData(event_loop_->monotonic_now(), true); })),
       server_statistics_fetcher_(
           configuration::MultiNode(event_loop_->configuration())
               ? event_loop_->MakeFetcher<message_bridge::ServerStatistics>(
@@ -167,8 +170,51 @@
   }
 }
 
+bool Logger::RenameLogBase(std::string new_base_name) {
+  if (new_base_name == log_namer_->base_name()) {
+    return true;
+  }
+  std::string current_directory = std::string(log_namer_->base_name());
+  std::string new_directory = new_base_name;
+
+  auto current_path_split = current_directory.rfind("/");
+  auto new_path_split = new_directory.rfind("/");
+
+  CHECK(new_base_name.substr(new_path_split) ==
+        current_directory.substr(current_path_split))
+      << "Rename of file base from " << current_directory << " to "
+      << new_directory << " is not supported.";
+
+  current_directory.resize(current_path_split);
+  new_directory.resize(new_path_split);
+  DIR *dir = opendir(current_directory.c_str());
+  if (dir) {
+    closedir(dir);
+    const int result = rename(current_directory.c_str(), new_directory.c_str());
+    if (result != 0) {
+      PLOG(ERROR) << "Unable to rename " << current_directory << " to "
+                  << new_directory;
+      return false;
+    }
+  } else {
+    // Handle if directory was already renamed.
+    dir = opendir(new_directory.c_str());
+    if (!dir) {
+      LOG(ERROR) << "Old directory " << current_directory
+                 << " missing and new directory " << new_directory
+                 << " not present.";
+      return false;
+    }
+    closedir(dir);
+  }
+
+  log_namer_->set_base_name(new_base_name);
+  Rotate();
+  return true;
+}
+
 void Logger::StartLogging(std::unique_ptr<LogNamer> log_namer,
-                          std::string_view log_start_uuid) {
+                          std::optional<UUID> log_start_uuid) {
   CHECK(!log_namer_) << ": Already logging";
   log_namer_ = std::move(log_namer);
 
@@ -219,6 +265,9 @@
     node_state_[node_index].log_file_header = MakeHeader(node, config_sha256);
   }
 
+  const aos::monotonic_clock::time_point beginning_time =
+      event_loop_->monotonic_now();
+
   // Grab data from each channel right before we declare the log file started
   // so we can capture the latest message on each channel.  This lets us have
   // non periodic messages with configuration that now get logged.
@@ -238,11 +287,18 @@
                  monotonic_clock::min_time, realtime_clock::min_time);
   }
 
+  const aos::monotonic_clock::time_point fetch_time =
+      event_loop_->monotonic_now();
   WriteHeader();
+  const aos::monotonic_clock::time_point header_time =
+      event_loop_->monotonic_now();
 
   LOG(INFO) << "Logging node as " << FlatbufferToJson(event_loop_->node())
-            << " start_time " << last_synchronized_time_ << " boot uuid "
-            << event_loop_->boot_uuid();
+            << " start_time " << last_synchronized_time_ << ", took "
+            << chrono::duration<double>(fetch_time - beginning_time).count()
+            << " to fetch, "
+            << chrono::duration<double>(header_time - fetch_time).count()
+            << " to write headers, boot uuid " << event_loop_->boot_uuid();
 
   // Force logging up until the start of the log file now, so the messages at
   // the start are always ordered before the rest of the messages.
@@ -264,7 +320,11 @@
   CHECK(log_namer_) << ": Not logging right now";
 
   if (end_time != aos::monotonic_clock::min_time) {
-    DoLogData(end_time);
+    // Folks like to use the on_logged_period_ callback to trigger stop and
+    // start events.  We can't have those then recurse and try to stop again.
+    // Rather than making everything reentrant, let's just instead block the
+    // callback here.
+    DoLogData(end_time, false);
   }
   timer_handler_->Disable();
 
@@ -276,7 +336,7 @@
   node_state_.clear();
 
   log_event_uuid_ = UUID::Zero();
-  log_start_uuid_ = std::string();
+  log_start_uuid_ = std::nullopt;
 
   return std::move(log_namer_);
 }
@@ -498,8 +558,8 @@
       logger_instance_uuid_.PackString(&fbb);
 
   flatbuffers::Offset<flatbuffers::String> log_start_uuid_offset;
-  if (!log_start_uuid_.empty()) {
-    log_start_uuid_offset = fbb.CreateString(log_start_uuid_);
+  if (log_start_uuid_) {
+    log_start_uuid_offset = fbb.CreateString(log_start_uuid_->ToString());
   }
 
   flatbuffers::Offset<flatbuffers::String> config_sha256_offset;
@@ -682,7 +742,7 @@
         CHECK(node_state_[f.data_node_index].header_valid)
             << ": Can't write data before the header on channel "
             << configuration::CleanedChannelToString(f.fetcher->channel());
-        f.writer->QueueSizedFlatbuffer(&fbb);
+        f.writer->QueueSizedFlatbuffer(&fbb, end);
       }
 
       if (f.timestamp_writer != nullptr) {
@@ -708,7 +768,7 @@
         CHECK(node_state_[f.timestamp_node_index].header_valid)
             << ": Can't write data before the header on channel "
             << configuration::CleanedChannelToString(f.fetcher->channel());
-        f.timestamp_writer->QueueSizedFlatbuffer(&fbb);
+        f.timestamp_writer->QueueSizedFlatbuffer(&fbb, end);
       }
 
       if (f.contents_writer != nullptr) {
@@ -769,7 +829,7 @@
         CHECK(node_state_[f.contents_node_index].header_valid)
             << ": Can't write data before the header on channel "
             << configuration::CleanedChannelToString(f.fetcher->channel());
-        f.contents_writer->QueueSizedFlatbuffer(&fbb);
+        f.contents_writer->QueueSizedFlatbuffer(&fbb, end);
       }
 
       f.written = true;
@@ -778,7 +838,8 @@
   last_synchronized_time_ = t;
 }
 
-void Logger::DoLogData(const monotonic_clock::time_point end_time) {
+void Logger::DoLogData(const monotonic_clock::time_point end_time,
+                       bool run_on_logged) {
   // We want to guarantee that messages aren't out of order by more than
   // max_out_of_order_duration.  To do this, we need sync points.  Every write
   // cycle should be a sync point.
@@ -788,7 +849,9 @@
     // per iteration, even if it is small.
     LogUntil(std::min(last_synchronized_time_ + polling_period_, end_time));
 
-    on_logged_period_();
+    if (run_on_logged) {
+      on_logged_period_();
+    }
 
     // If we missed cycles, we could be pretty far behind.  Spin until we are
     // caught up.
diff --git a/aos/events/logging/log_writer.h b/aos/events/logging/log_writer.h
index 992633a..8131a31 100644
--- a/aos/events/logging/log_writer.h
+++ b/aos/events/logging/log_writer.h
@@ -62,8 +62,9 @@
   void set_polling_period(std::chrono::nanoseconds polling_period) {
     polling_period_ = polling_period;
   }
+  std::chrono::nanoseconds polling_period() const { return polling_period_; }
 
-  std::string_view log_start_uuid() const { return log_start_uuid_; }
+  std::optional<UUID> log_start_uuid() const { return log_start_uuid_; }
   UUID logger_instance_uuid() const { return logger_instance_uuid_; }
 
   // The maximum time for a single fetch which returned a message, or 0 if none
@@ -125,7 +126,12 @@
   // multiple nodes. The default (empty string) indicates there isn't one
   // available.
   void StartLogging(std::unique_ptr<LogNamer> log_namer,
-                    std::string_view log_start_uuid = "");
+                    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.
+  // Only renaming the folder is supported, not the file base name.
+  bool RenameLogBase(std::string new_base_name);
 
   // Stops logging. Ensures any messages through end_time make it into the log.
   //
@@ -148,6 +154,15 @@
     });
   }
 
+  // Shortcut to call StartLogging with a MultiNodeLogNamer when event
+  // processing starts.
+  void StartLoggingOnRun(std::string base_name) {
+    event_loop_->OnRun([this, base_name]() {
+      StartLogging(std::make_unique<MultiNodeLogNamer>(
+          base_name, event_loop_->configuration(), event_loop_->node()));
+    });
+  }
+
  private:
   // Structure to track both a fetcher, and if the data fetched has been
   // written.  We may want to delay writing data to disk so that we don't let
@@ -243,7 +258,8 @@
       aos::monotonic_clock::time_point monotonic_start_time,
       aos::realtime_clock::time_point realtime_start_time);
 
-  void DoLogData(const monotonic_clock::time_point end_time);
+  void DoLogData(const monotonic_clock::time_point end_time,
+                 bool run_on_logged);
 
   void WriteMissingTimestamps();
 
@@ -275,7 +291,7 @@
   const UUID logger_instance_uuid_ = UUID::Random();
   std::unique_ptr<LogNamer> log_namer_;
   // Empty indicates there isn't one.
-  std::string log_start_uuid_;
+  std::optional<UUID> log_start_uuid_;
 
   // Name to save in the log file.  Defaults to hostname.
   std::string name_;
diff --git a/aos/events/logging/logfile_utils.cc b/aos/events/logging/logfile_utils.cc
index 686e0a8..b8b66a2 100644
--- a/aos/events/logging/logfile_utils.cc
+++ b/aos/events/logging/logfile_utils.cc
@@ -30,6 +30,9 @@
 
 DEFINE_int32(flush_size, 128000,
              "Number of outstanding bytes to allow before flushing to disk.");
+DEFINE_double(
+    flush_period, 5.0,
+    "Max time to let data sit in the queue before flushing in seconds.");
 
 DEFINE_double(
     max_out_of_order, -1,
@@ -98,6 +101,7 @@
     return;
   }
 
+  aos::monotonic_clock::time_point now;
   if (encoder_->may_bypass() && span.size() > 4096u) {
     // Over this threshold, we'll assume it's cheaper to add an extra
     // syscall to write the data immediately instead of copying it to
@@ -114,11 +118,13 @@
     const auto end = aos::monotonic_clock::now();
     HandleWriteReturn(written, span.size());
     UpdateStatsForWrite(end - start, written, 1);
+    now = end;
   } else {
     encoder_->Encode(CopySpanAsDetachedBuffer(span));
+    now = aos::monotonic_clock::now();
   }
 
-  FlushAtThreshold();
+  FlushAtThreshold(now);
 }
 
 void DetachedBufferWriter::Close() {
@@ -141,16 +147,21 @@
 }
 
 void DetachedBufferWriter::Flush() {
-  const auto queue = encoder_->queue();
-  if (queue.empty()) {
-    return;
-  }
   if (ran_out_of_space_) {
     // We don't want any later data to be written after space becomes available,
     // so refuse to write anything more once we've dropped data because we ran
     // out of space.
-    VLOG(1) << "Ignoring queue: " << queue.size();
-    encoder_->Clear(queue.size());
+    if (encoder_) {
+      VLOG(1) << "Ignoring queue: " << encoder_->queue().size();
+      encoder_->Clear(encoder_->queue().size());
+    } else {
+      VLOG(1) << "No queue to ignore";
+    }
+    return;
+  }
+
+  const auto queue = encoder_->queue();
+  if (queue.empty()) {
     return;
   }
 
@@ -204,12 +215,37 @@
   total_write_bytes_ += written;
 }
 
-void DetachedBufferWriter::FlushAtThreshold() {
+void DetachedBufferWriter::FlushAtThreshold(
+    aos::monotonic_clock::time_point now) {
+  if (ran_out_of_space_) {
+    // We don't want any later data to be written after space becomes available,
+    // so refuse to write anything more once we've dropped data because we ran
+    // out of space.
+    if (encoder_) {
+      VLOG(1) << "Ignoring queue: " << encoder_->queue().size();
+      encoder_->Clear(encoder_->queue().size());
+    } else {
+      VLOG(1) << "No queue to ignore";
+    }
+    return;
+  }
+
+  // We don't want to flush the first time through.  Otherwise we will flush as
+  // the log file header might be compressing, defeating any parallelism and
+  // queueing there.
+  if (last_flush_time_ == aos::monotonic_clock::min_time) {
+    last_flush_time_ = now;
+  }
+
   // Flush if we are at the max number of iovs per writev, because there's no
   // point queueing up any more data in memory. Also flush once we have enough
-  // data queued up.
+  // data queued up or if it has been long enough.
   while (encoder_->queued_bytes() > static_cast<size_t>(FLAGS_flush_size) ||
-         encoder_->queue_size() >= IOV_MAX) {
+         encoder_->queue_size() >= IOV_MAX ||
+         now > last_flush_time_ +
+                   chrono::duration_cast<chrono::nanoseconds>(
+                       chrono::duration<double>(FLAGS_flush_period))) {
+    last_flush_time_ = now;
     Flush();
   }
 }
diff --git a/aos/events/logging/logfile_utils.h b/aos/events/logging/logfile_utils.h
index d251772..2219a07 100644
--- a/aos/events/logging/logfile_utils.h
+++ b/aos/events/logging/logfile_utils.h
@@ -71,16 +71,22 @@
   // Triggers a flush if there's enough data queued up.
   //
   // Steals the detached buffer from it.
-  void QueueSizedFlatbuffer(flatbuffers::FlatBufferBuilder *fbb) {
-    QueueSizedFlatbuffer(fbb->Release());
+  void QueueSizedFlatbuffer(flatbuffers::FlatBufferBuilder *fbb,
+                            aos::monotonic_clock::time_point now) {
+    QueueSizedFlatbuffer(fbb->Release(), now);
   }
   // May steal the backing storage of buffer, or may leave it alone.
+  void QueueSizedFlatbuffer(flatbuffers::DetachedBuffer &&buffer,
+                            aos::monotonic_clock::time_point now) {
+    QueueSizedFlatbuffer(std::move(buffer));
+    FlushAtThreshold(now);
+  }
+  // Unconditionally queues the buffer.
   void QueueSizedFlatbuffer(flatbuffers::DetachedBuffer &&buffer) {
     if (ran_out_of_space_) {
       return;
     }
     encoder_->Encode(std::move(buffer));
-    FlushAtThreshold();
   }
 
   // Queues up data in span. May copy or may write it to disk immediately.
@@ -107,7 +113,12 @@
   void Close();
 
   // Returns the total number of bytes written and currently queued.
-  size_t total_bytes() const { return encoder_->total_bytes(); }
+  size_t total_bytes() const {
+    if (!encoder_) {
+      return 0;
+    }
+    return encoder_->total_bytes();
+  }
 
   // The maximum time for a single write call, or 0 if none have been performed.
   std::chrono::nanoseconds max_write_time() const { return max_write_time_; }
@@ -154,8 +165,10 @@
                            ssize_t written, int iovec_size);
 
   // Flushes data if we've reached the threshold to do that as part of normal
-  // operation.
-  void FlushAtThreshold();
+  // operation either due to the outstanding queued data, or because we have
+  // passed our flush period.  now is the current time to save some CPU grabbing
+  // the current time.  It just needs to be close.
+  void FlushAtThreshold(aos::monotonic_clock::time_point now);
 
   std::string filename_;
   std::unique_ptr<DetachedBufferEncoder> encoder_;
@@ -175,6 +188,9 @@
   int total_write_count_ = 0;
   int total_write_messages_ = 0;
   int total_write_bytes_ = 0;
+
+  aos::monotonic_clock::time_point last_flush_time_ =
+      aos::monotonic_clock::min_time;
 };
 
 // Packes a message pointed to by the context into a MessageHeader.
diff --git a/aos/events/logging/logfile_utils_test.cc b/aos/events/logging/logfile_utils_test.cc
index 8e29335..384772c 100644
--- a/aos/events/logging/logfile_utils_test.cc
+++ b/aos/events/logging/logfile_utils_test.cc
@@ -255,6 +255,7 @@
     const aos::FlatbufferDetachedBuffer<Configuration> &config,
     const std::string_view json) {
   flatbuffers::FlatBufferBuilder fbb;
+  fbb.ForceDefaults(true);
   flatbuffers::Offset<Configuration> config_offset =
       aos::CopyFlatBuffer(config, &fbb);
   LogFileHeader::Builder header_builder(fbb);
@@ -266,6 +267,7 @@
       JsonToFlatbuffer<LogFileHeader>(json));
   CHECK(header_updates.Verify());
   flatbuffers::FlatBufferBuilder fbb2;
+  fbb2.ForceDefaults(true);
   fbb2.FinishSizePrefixed(
       aos::MergeFlatBuffers(config_header, header_updates, &fbb2));
   return fbb2.Release();
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index d8ab66e..13b2312 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -1,5 +1,7 @@
 #include "aos/events/logging/log_reader.h"
 
+#include <sys/stat.h>
+
 #include "absl/strings/str_format.h"
 #include "aos/events/event_loop.h"
 #include "aos/events/logging/log_writer.h"
@@ -452,17 +454,17 @@
     event_loop_factory_.SetTimeConverter(&time_converter_);
 
     // Go through and remove the logfiles if they already exist.
-    for (const auto file : logfiles_) {
+    for (const auto &file : logfiles_) {
       unlink(file.c_str());
       unlink((file + ".xz").c_str());
     }
 
-    for (const auto file :
+    for (const auto &file :
          MakeLogFiles(tmp_dir_ + "/relogged1", tmp_dir_ + "/relogged2")) {
       unlink(file.c_str());
     }
 
-    for (const auto file : pi1_reboot_logfiles_) {
+    for (const auto &file : pi1_reboot_logfiles_) {
       unlink(file.c_str());
     }
 
@@ -2077,6 +2079,48 @@
   }
 }
 
+// Test that renaming the base, renames the folder.
+TEST_F(MultinodeLoggerTest, LoggerRenameFolder) {
+  time_converter_.AddMonotonic(
+      {monotonic_clock::epoch(),
+       monotonic_clock::epoch() + chrono::seconds(1000)});
+  logfile_base1_ = tmp_dir_ + "/renamefolder/multi_logfile1";
+  logfile_base2_ = tmp_dir_ + "/renamefolder/multi_logfile2";
+  logfiles_ = MakeLogFiles(logfile_base1_, logfile_base2_);
+  LoggerState pi1_logger = MakeLogger(pi1_);
+  LoggerState pi2_logger = MakeLogger(pi2_);
+
+  StartLogger(&pi1_logger);
+  StartLogger(&pi2_logger);
+
+  event_loop_factory_.RunFor(chrono::milliseconds(10000));
+  logfile_base1_ = tmp_dir_ + "/new-good/multi_logfile1";
+  logfile_base2_ = tmp_dir_ + "/new-good/multi_logfile2";
+  logfiles_ = MakeLogFiles(logfile_base1_, logfile_base2_);
+  ASSERT_TRUE(pi1_logger.logger->RenameLogBase(logfile_base1_));
+  ASSERT_TRUE(pi2_logger.logger->RenameLogBase(logfile_base2_));
+  for (auto &file : logfiles_) {
+    struct stat s;
+    EXPECT_EQ(0, stat(file.c_str(), &s));
+  }
+}
+
+// Test that renaming the file base dies.
+TEST_P(MultinodeLoggerDeathTest, LoggerRenameFile) {
+  time_converter_.AddMonotonic(
+      {monotonic_clock::epoch(),
+       monotonic_clock::epoch() + chrono::seconds(1000)});
+  logfile_base1_ = tmp_dir_ + "/renamefile/multi_logfile1";
+  logfile_base2_ = tmp_dir_ + "/renamefile/multi_logfile2";
+  logfiles_ = MakeLogFiles(logfile_base1_, logfile_base2_);
+  LoggerState pi1_logger = MakeLogger(pi1_);
+  StartLogger(&pi1_logger);
+  event_loop_factory_.RunFor(chrono::milliseconds(10000));
+  logfile_base1_ = tmp_dir_ + "/new-renamefile/new_multi_logfile1";
+  EXPECT_DEATH({ pi1_logger.logger->RenameLogBase(logfile_base1_); },
+               "Rename of file base from");
+}
+
 // TODO(austin): We can write a test which recreates a logfile and confirms that
 // we get it back.  That is the ultimate test.
 
@@ -2200,9 +2244,9 @@
 }
 
 constexpr std::string_view kCombinedConfigSha1(
-    "8d17eb7c2347fd4a8a9a2e0f171a91338fe4d5dd705829c39497608075a8d6fc");
+    "0184681f8b83b5b9902a88ab12504c06b780907f6d156353bd958ebcf9389ef9");
 constexpr std::string_view kSplitConfigSha1(
-    "a6235491429b7b062e5da35c1d0d279c7e7e33cd70787f231d420ab831959744");
+    "1020274679a8f8c15ea20a48e4a35dd59a435203e5f31a57e15355e5a6ee31f7");
 
 INSTANTIATE_TEST_CASE_P(
     All, MultinodeLoggerTest,
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index 8474bb8..ef34839 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -728,6 +728,7 @@
 }
 
 void SimulatedWatcher::HandleEvent() {
+  VLOG(1) << "Watcher " << configuration::CleanedChannelToString(channel_);
   CHECK_NE(msgs_.size(), 0u) << ": No events to handle.";
 
   const monotonic_clock::time_point monotonic_now =
@@ -919,6 +920,7 @@
 }
 
 void SimulatedTimerHandler::HandleEvent() {
+  VLOG(1) << "Timer " << name();
   const ::aos::monotonic_clock::time_point monotonic_now =
       simulated_event_loop_->monotonic_now();
   logging::ScopedLogRestorer prev_logger;
@@ -974,6 +976,7 @@
 }
 
 void SimulatedPhasedLoopHandler::HandleEvent() {
+  VLOG(1) << "Phased loop " << name();
   monotonic_clock::time_point monotonic_now =
       simulated_event_loop_->monotonic_now();
   logging::ScopedLogRestorer prev_logger;
diff --git a/aos/events/simulated_event_loop_test.cc b/aos/events/simulated_event_loop_test.cc
index 39dbe99..34e10ca 100644
--- a/aos/events/simulated_event_loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -571,6 +571,7 @@
             LOG(FATAL) << "Unknown connection";
           }
 
+          EXPECT_EQ(connection->partial_deliveries(), 0);
           EXPECT_TRUE(connection->has_monotonic_offset());
           EXPECT_EQ(connection->monotonic_offset(), 150000);
         }
@@ -588,6 +589,7 @@
             stats.connections()->Get(0);
         EXPECT_EQ(connection->state(), message_bridge::State::CONNECTED);
         EXPECT_GT(connection->received_packets(), 50);
+        EXPECT_EQ(connection->partial_deliveries(), 0);
         EXPECT_TRUE(connection->has_monotonic_offset());
         EXPECT_EQ(connection->monotonic_offset(), 150000);
         ++pi2_client_statistics_count;
@@ -604,6 +606,7 @@
             stats.connections()->Get(0);
         EXPECT_EQ(connection->state(), message_bridge::State::CONNECTED);
         EXPECT_GE(connection->received_packets(), 5);
+        EXPECT_EQ(connection->partial_deliveries(), 0);
         EXPECT_TRUE(connection->has_monotonic_offset());
         EXPECT_EQ(connection->monotonic_offset(), 150000);
         ++pi3_client_statistics_count;
diff --git a/aos/network/message_bridge_client.fbs b/aos/network/message_bridge_client.fbs
index 7056506..6efe3a9 100644
--- a/aos/network/message_bridge_client.fbs
+++ b/aos/network/message_bridge_client.fbs
@@ -21,6 +21,10 @@
   // Number of duplicate packets we received and dropped.
   duplicate_packets:uint (id: 4);
 
+  // Number of extra calls needed to receive a single message
+  // (indicates congestion)
+  partial_deliveries:uint (id: 5);
+
   // TODO(austin): Per channel counts?
 }
 
diff --git a/aos/network/message_bridge_client_lib.cc b/aos/network/message_bridge_client_lib.cc
index a5113a0..08350a8 100644
--- a/aos/network/message_bridge_client_lib.cc
+++ b/aos/network/message_bridge_client_lib.cc
@@ -238,6 +238,8 @@
     // Duplicate message, ignore.
   } else {
     connection_->mutate_received_packets(connection_->received_packets() + 1);
+    connection_->mutate_partial_deliveries(connection_->partial_deliveries() +
+                                           message->partial_deliveries);
 
     channel_state->last_queue_index = remote_data->queue_index();
     channel_state->last_timestamp = monotonic_clock::time_point(
diff --git a/aos/network/message_bridge_client_status.cc b/aos/network/message_bridge_client_status.cc
index e8520cf..69f474a 100644
--- a/aos/network/message_bridge_client_status.cc
+++ b/aos/network/message_bridge_client_status.cc
@@ -33,6 +33,7 @@
     connection_builder.add_received_packets(0);
     connection_builder.add_duplicate_packets(0);
     connection_builder.add_monotonic_offset(0);
+    connection_builder.add_partial_deliveries(0);
     connection_offsets.emplace_back(connection_builder.Finish());
   }
   flatbuffers::Offset<
@@ -97,6 +98,8 @@
       client_connection_builder.add_duplicate_packets(
           connection->duplicate_packets());
     }
+    client_connection_builder.add_partial_deliveries(
+        connection->partial_deliveries());
 
     // Strip out the monotonic offset if it isn't populated.
     TimestampFilter *filter = &filters_[client_connection_offsets_.size()];
diff --git a/aos/network/message_bridge_server.fbs b/aos/network/message_bridge_server.fbs
index fa73ba5..cdf970c 100644
--- a/aos/network/message_bridge_server.fbs
+++ b/aos/network/message_bridge_server.fbs
@@ -19,7 +19,7 @@
   // Number of packets that have been dropped (if known).
   dropped_packets:uint (id: 2);
 
-  // Number of packets received on all channels.
+  // Number of packets sent on all channels.
   sent_packets:uint (id: 3);
 
   // This is the measured monotonic offset for the connected node in
@@ -30,6 +30,10 @@
   // Boot UUID of the client.
   boot_uuid:string (id: 5);
 
+  // Number of extra calls needed to receive a single message
+  // (indicates congestion)
+  partial_deliveries:uint (id: 6);
+
   // TODO(austin): Per channel counts?
 }
 
diff --git a/aos/network/message_bridge_server_lib.cc b/aos/network/message_bridge_server_lib.cc
index 77fe1e4..ea75693 100644
--- a/aos/network/message_bridge_server_lib.cc
+++ b/aos/network/message_bridge_server_lib.cc
@@ -112,9 +112,10 @@
   // and flushes.  Whee.
 }
 
-void ChannelState::HandleDelivery(
-    sctp_assoc_t rcv_assoc_id, uint16_t /*ssn*/, absl::Span<const uint8_t> data,
-    const MessageBridgeServerStatus &server_status) {
+void ChannelState::HandleDelivery(sctp_assoc_t rcv_assoc_id, uint16_t /*ssn*/,
+                                  absl::Span<const uint8_t> data,
+                                  uint32_t partial_deliveries,
+                                  MessageBridgeServerStatus *server_status) {
   const logger::MessageHeader *message_header =
       flatbuffers::GetRoot<logger::MessageHeader>(data.data());
   for (Peer &peer : peers_) {
@@ -130,7 +131,7 @@
             peer.timestamp_logger->MakeBuilder();
 
         flatbuffers::Offset<flatbuffers::Vector<uint8_t>> boot_uuid_offset =
-            server_status.BootUUID(peer.node_index).PackVector(builder.fbb());
+            server_status->BootUUID(peer.node_index).PackVector(builder.fbb());
 
         RemoteMessage::Builder remote_message_builder =
             builder.MakeBuilder<RemoteMessage>();
@@ -155,6 +156,9 @@
             message_header->queue_index());
         remote_message_builder.add_boot_uuid(boot_uuid_offset);
 
+        server_status->AddPartialDeliveries(peer.node_index,
+                                            partial_deliveries);
+
         builder.Send(remote_message_builder.Finish());
       }
       break;
@@ -422,6 +426,7 @@
                    ->string_view();
     server_status_.ResetFilter(node_index);
     server_status_.ClearBootUUID(node_index);
+    server_status_.ResetPartialDeliveries(node_index);
   }
 }
 
@@ -495,7 +500,10 @@
         ++channel_index;
       }
     }
+    // TODO(sarah.newman): what if node_index is -1?
     server_status_.ResetFilter(node_index);
+    server_status_.AddPartialDeliveries(node_index,
+                                        message->partial_deliveries);
     server_status_.SetBootUUID(
         node_index, UUID::FromString(connect->boot_uuid()->string_view()));
     VLOG(1) << "Resetting filters for " << node_index << " "
@@ -515,7 +523,7 @@
             message->header.rcvinfo.rcv_assoc_id,
             message->header.rcvinfo.rcv_ssn,
             absl::Span<const uint8_t>(message->data(), message->size),
-            server_status_);
+            message->partial_deliveries, &server_status_);
   }
 
   if (VLOG_IS_ON(1)) {
diff --git a/aos/network/message_bridge_server_lib.h b/aos/network/message_bridge_server_lib.h
index be1801c..7ff4e3a 100644
--- a/aos/network/message_bridge_server_lib.h
+++ b/aos/network/message_bridge_server_lib.h
@@ -85,7 +85,8 @@
   // Handles reception of delivery times.
   void HandleDelivery(sctp_assoc_t rcv_assoc_id, uint16_t ssn,
                       absl::Span<const uint8_t> data,
-                      const MessageBridgeServerStatus &server_status);
+                      uint32_t partial_deliveries,
+                      MessageBridgeServerStatus *server_status);
 
   // Handles (by consuming) failure to deliver a message.
   void HandleFailure(
diff --git a/aos/network/message_bridge_server_status.cc b/aos/network/message_bridge_server_status.cc
index 06f88ed..48b442a 100644
--- a/aos/network/message_bridge_server_status.cc
+++ b/aos/network/message_bridge_server_status.cc
@@ -36,6 +36,7 @@
     connection_builder.add_dropped_packets(0);
     connection_builder.add_sent_packets(0);
     connection_builder.add_monotonic_offset(0);
+    connection_builder.add_partial_deliveries(0);
     connection_offsets.emplace_back(connection_builder.Finish());
   }
   flatbuffers::Offset<
@@ -85,6 +86,7 @@
       statistics_.message().connections()->size());
 
   filters_.resize(event_loop->configuration()->nodes()->size());
+  partial_deliveries_.resize(event_loop->configuration()->nodes()->size());
   boot_uuids_.resize(event_loop->configuration()->nodes()->size(), UUID::Zero());
   has_boot_uuids_.resize(event_loop->configuration()->nodes()->size(), false);
   timestamp_fetchers_.resize(event_loop->configuration()->nodes()->size());
@@ -191,6 +193,8 @@
     server_connection_builder.add_dropped_packets(
         connection->dropped_packets());
     server_connection_builder.add_sent_packets(connection->sent_packets());
+    server_connection_builder.add_partial_deliveries(
+        partial_deliveries_[node_index]);
 
     // TODO(austin): If it gets stale, drop it too.
     if (!filters_[node_index].MissingSamples()) {
diff --git a/aos/network/message_bridge_server_status.h b/aos/network/message_bridge_server_status.h
index 52fc174..04b30de 100644
--- a/aos/network/message_bridge_server_status.h
+++ b/aos/network/message_bridge_server_status.h
@@ -49,6 +49,18 @@
   // one.
   const UUID &BootUUID(int node_index) const { return boot_uuids_[node_index]; }
 
+  void AddPartialDeliveries(int node_index, uint32_t partial_deliveries) {
+    partial_deliveries_[node_index] += partial_deliveries;
+  }
+
+  void ResetPartialDeliveries(int node_index) {
+    partial_deliveries_[node_index] = 0;
+  }
+
+  uint32_t PartialDeliveries(int node_index) const {
+    return partial_deliveries_[node_index];
+  }
+
   // Returns the ServerConnection message which is updated by the server.
   ServerConnection *FindServerConnection(std::string_view node_name);
   ServerConnection *FindServerConnection(const Node *node);
@@ -105,6 +117,8 @@
   std::function<void(const Context &)> send_data_;
 
   bool send_ = true;
+
+  std::vector<uint32_t> partial_deliveries_;
 };
 
 
diff --git a/aos/network/message_bridge_test.cc b/aos/network/message_bridge_test.cc
index 1b6f594..7420579 100644
--- a/aos/network/message_bridge_test.cc
+++ b/aos/network/message_bridge_test.cc
@@ -1067,6 +1067,11 @@
                   ->duplicate_packets(),
               0u);
 
+    EXPECT_EQ(pi2_client_statistics_fetcher->connections()
+                  ->Get(0)
+                  ->partial_deliveries(),
+              0u);
+
     EXPECT_TRUE(ping_fetcher.Fetch());
     EXPECT_FALSE(unreliable_ping_fetcher.Fetch());
     EXPECT_EQ(ping_timestamp_count, 1);
@@ -1087,6 +1092,11 @@
                   ->duplicate_packets(),
               1u);
 
+    EXPECT_EQ(pi2_client_statistics_fetcher->connections()
+                  ->Get(0)
+                  ->partial_deliveries(),
+              0u);
+
     EXPECT_EQ(ping_timestamp_count, 1);
     EXPECT_FALSE(ping_fetcher.Fetch());
     EXPECT_FALSE(unreliable_ping_fetcher.Fetch());
@@ -1192,6 +1202,11 @@
                   ->duplicate_packets(),
               0u);
 
+    EXPECT_EQ(pi2_client_statistics_fetcher->connections()
+                  ->Get(0)
+                  ->partial_deliveries(),
+              0u);
+
     EXPECT_TRUE(ping_fetcher.Fetch());
     EXPECT_FALSE(unreliable_ping_fetcher.Fetch());
     EXPECT_EQ(ping_timestamp_count, 1);
@@ -1213,6 +1228,12 @@
                   ->duplicate_packets(),
               1u);
 
+
+    EXPECT_EQ(pi2_client_statistics_fetcher->connections()
+                  ->Get(0)
+                  ->partial_deliveries(),
+              0u);
+
     EXPECT_EQ(ping_timestamp_count, 1);
     EXPECT_FALSE(ping_fetcher.Fetch());
     EXPECT_FALSE(unreliable_ping_fetcher.Fetch());
diff --git a/aos/network/sctp_client.cc b/aos/network/sctp_client.cc
index d77392e..7d86316 100644
--- a/aos/network/sctp_client.cc
+++ b/aos/network/sctp_client.cc
@@ -25,10 +25,14 @@
   PCHECK(fd_ != -1);
 
   {
-    // Allow the kernel to deliver messages from different streams in any order.
-    int full_interleaving = 2;
+    // Per https://tools.ietf.org/html/rfc6458
+    // Setting this to !0 allows event notifications to be interleaved
+    // with data if enabled, and would have to be handled in the code.
+    // Enabling interleaving would only matter during congestion, which
+    // typically only happens during application startup.
+    int interleaving = 0;
     PCHECK(setsockopt(fd_, IPPROTO_SCTP, SCTP_FRAGMENT_INTERLEAVE,
-                      &full_interleaving, sizeof(full_interleaving)) == 0);
+                      &interleaving, sizeof(interleaving)) == 0);
   }
 
   {
@@ -57,7 +61,6 @@
     // stack out in the wild for linux is old and primitive.
     struct sctp_event_subscribe subscribe;
     memset(&subscribe, 0, sizeof(subscribe));
-    subscribe.sctp_data_io_event = 1;
     subscribe.sctp_association_event = 1;
     subscribe.sctp_stream_change_event = 1;
     PCHECK(setsockopt(fd_, SOL_SCTP, SCTP_EVENTS, (char *)&subscribe,
diff --git a/aos/network/sctp_lib.cc b/aos/network/sctp_lib.cc
index b82c1eb..b522851 100644
--- a/aos/network/sctp_lib.cc
+++ b/aos/network/sctp_lib.cc
@@ -134,8 +134,7 @@
       VLOG(1) << "\t\t(remote_error: err=" << ntohs(sre->sre_error) << ")";
     } break;
     case SCTP_STREAM_CHANGE_EVENT: {
-      const struct sctp_stream_change_event *sce =
-          &snp->sn_strchange_event;
+      const struct sctp_stream_change_event *sce = &snp->sn_strchange_event;
       LOG(INFO) << " SCTP_STREAM_CHANGE_EVENT";
       VLOG(1) << "\t\t(stream_change_event: flags=" << sce->strchange_flags
               << ", assoc_id=" << sce->strchange_assoc_id
@@ -181,54 +180,85 @@
             << " sstat_primary.spinfo_rto:" << status.sstat_primary.spinfo_rto;
 }
 
-aos::unique_c_ptr<Message> ReadSctpMessage(int fd, int max_size) {
+aos::unique_c_ptr<Message> ReadSctpMessage(int fd, size_t max_size) {
   char incmsg[CMSG_SPACE(sizeof(_sctp_cmsg_data_t))];
   struct iovec iov;
   struct msghdr inmessage;
 
-  memset(&inmessage, 0, sizeof(struct msghdr));
-
   aos::unique_c_ptr<Message> result(
       reinterpret_cast<Message *>(malloc(sizeof(Message) + max_size + 1)));
+  result->size = 0;
 
-  iov.iov_len = max_size + 1;
-  iov.iov_base = result->mutable_data();
+  int count = 0;
+  int last_flags = 0;
+  for (count = 0; !(last_flags & MSG_EOR); count++) {
+    memset(&inmessage, 0, sizeof(struct msghdr));
 
-  inmessage.msg_iov = &iov;
-  inmessage.msg_iovlen = 1;
+    iov.iov_len = max_size + 1 - result->size;
+    iov.iov_base = result->mutable_data() + result->size;
 
-  inmessage.msg_control = incmsg;
-  inmessage.msg_controllen = sizeof(incmsg);
+    inmessage.msg_iov = &iov;
+    inmessage.msg_iovlen = 1;
 
-  inmessage.msg_namelen = sizeof(struct sockaddr_storage);
-  inmessage.msg_name = &result->sin;
+    inmessage.msg_control = incmsg;
+    inmessage.msg_controllen = sizeof(incmsg);
 
-  ssize_t size;
-  PCHECK((size = recvmsg(fd, &inmessage, 0)) > 0);
+    inmessage.msg_namelen = sizeof(struct sockaddr_storage);
+    inmessage.msg_name = &result->sin;
 
-  result->size = size;
+    ssize_t size;
+    PCHECK((size = recvmsg(fd, &inmessage, 0)) > 0);
+
+    if (count > 0) {
+      VLOG(1) << "Count: " << count;
+      VLOG(1) << "Last msg_flags: " << last_flags;
+      VLOG(1) << "msg_flags: " << inmessage.msg_flags;
+      VLOG(1) << "Current size: " << result->size;
+      VLOG(1) << "Received size: " << size;
+      CHECK_EQ(MSG_NOTIFICATION & inmessage.msg_flags, MSG_NOTIFICATION & last_flags);
+    }
+
+    result->size += size;
+    last_flags = inmessage.msg_flags;
+
+    for (struct cmsghdr *scmsg = CMSG_FIRSTHDR(&inmessage); scmsg != NULL;
+         scmsg = CMSG_NXTHDR(&inmessage, scmsg)) {
+      switch (scmsg->cmsg_type) {
+        case SCTP_RCVINFO: {
+          struct sctp_rcvinfo *data = reinterpret_cast<struct sctp_rcvinfo *>(CMSG_DATA(scmsg));
+          if (count > 0) {
+            VLOG(1) << "Got sctp_rcvinfo on continued packet";
+            CHECK_EQ(result->header.rcvinfo.rcv_sid, data->rcv_sid);
+            CHECK_EQ(result->header.rcvinfo.rcv_ssn, data->rcv_ssn);
+            CHECK_EQ(result->header.rcvinfo.rcv_ppid, data->rcv_ppid);
+            CHECK_EQ(result->header.rcvinfo.rcv_assoc_id, data->rcv_assoc_id);
+          }
+          result->header.rcvinfo = *data;
+        } break;
+        default:
+          LOG(INFO) << "\tUnknown type: " << scmsg->cmsg_type;
+          break;
+      }
+    }
+
+    CHECK_NE(inmessage.msg_flags & MSG_CTRUNC, MSG_CTRUNC)
+        << ": Control message truncated.";
+
+    CHECK_LE(result->size, max_size) << ": Message overflowed buffer on stream "
+                                     << result->header.rcvinfo.rcv_sid << ".";
+  }
+
+  result->partial_deliveries = count - 1;
+  if (count > 1) {
+    VLOG(1) << "Final count: " << count;
+    VLOG(1) << "Final size: " << result->size;
+  }
+
   if ((MSG_NOTIFICATION & inmessage.msg_flags)) {
     result->message_type = Message::kNotification;
   } else {
     result->message_type = Message::kMessage;
   }
-
-  for (struct cmsghdr *scmsg = CMSG_FIRSTHDR(&inmessage); scmsg != NULL;
-       scmsg = CMSG_NXTHDR(&inmessage, scmsg)) {
-    switch (scmsg->cmsg_type) {
-      case SCTP_RCVINFO: {
-        struct sctp_rcvinfo *data = (struct sctp_rcvinfo *)CMSG_DATA(scmsg);
-        result->header.rcvinfo = *data;
-      } break;
-      default:
-        LOG(INFO) << "\tUnknown type: " << scmsg->cmsg_type;
-        break;
-    }
-  }
-
-  CHECK_LE(size, max_size) << ": Message overflowed buffer on stream "
-                           << result->header.rcvinfo.rcv_sid << ".";
-
   return result;
 }
 
diff --git a/aos/network/sctp_lib.h b/aos/network/sctp_lib.h
index 9a1274a..265d1f5 100644
--- a/aos/network/sctp_lib.h
+++ b/aos/network/sctp_lib.h
@@ -52,6 +52,8 @@
     return reinterpret_cast<const uint8_t *>(&actual_data[0].data);
   }
 
+  uint32_t partial_deliveries = 0;
+
   // Returns a human readable peer IP address.
   std::string PeerAddress() const;
 
@@ -70,7 +72,7 @@
 void LogSctpStatus(int fd, sctp_assoc_t assoc_id);
 
 // Read and allocate a message.
-aos::unique_c_ptr<Message> ReadSctpMessage(int fd, int max_size);
+aos::unique_c_ptr<Message> ReadSctpMessage(int fd, size_t max_size);
 
 // Returns the max network buffer available for reading for a socket.
 size_t ReadRMemMax();
diff --git a/aos/network/sctp_server.cc b/aos/network/sctp_server.cc
index 8bf14f6..537f3ab 100644
--- a/aos/network/sctp_server.cc
+++ b/aos/network/sctp_server.cc
@@ -30,7 +30,6 @@
     {
       struct sctp_event_subscribe subscribe;
       memset(&subscribe, 0, sizeof(subscribe));
-      subscribe.sctp_data_io_event = 1;
       subscribe.sctp_association_event = 1;
       subscribe.sctp_send_failure_event = 1;
       subscribe.sctp_partial_delivery_event = 1;
@@ -45,10 +44,14 @@
                         sizeof(int)) == 0);
     }
     {
-      // Allow one packet on the wire to have multiple source packets.
-      int full_interleaving = 2;
+      // Per https://tools.ietf.org/html/rfc6458
+      // Setting this to !0 allows event notifications to be interleaved
+      // with data if enabled, and would have to be handled in the code.
+      // Enabling interleaving would only matter during congestion, which
+      // typically only happens during application startup.
+      int interleaving = 0;
       PCHECK(setsockopt(fd_, IPPROTO_SCTP, SCTP_FRAGMENT_INTERLEAVE,
-                        &full_interleaving, sizeof(full_interleaving)) == 0);
+                        &interleaving, sizeof(interleaving)) == 0);
     }
     {
       // Turn off the NAGLE algorithm.
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index b08e96f..4e6f373 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -643,6 +643,7 @@
         ":drivetrain_config",
         ":spline_goal_fbs",
         ":trajectory_fbs",
+        "//aos/util:math",
         "//frc971/control_loops:c2d",
         "//frc971/control_loops:dlqr",
         "//frc971/control_loops:hybrid_state_feedback_loop",
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.json b/frc971/control_loops/drivetrain/drivetrain_config.json
index 3438fe5..238adee 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.json
+++ b/frc971/control_loops/drivetrain/drivetrain_config.json
@@ -11,8 +11,8 @@
     {
       "name": "/drivetrain",
       "type": "frc971.control_loops.drivetrain.fb.Trajectory",
-      "max_size": 400000,
-      "frequency": 2,
+      "max_size": 600000,
+      "frequency": 4,
       "num_senders": 2,
       "read_method": "PIN",
       "num_readers": 6
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index 26428ba..1b353a1 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -811,9 +811,25 @@
       CHECK_NOTNULL(drivetrain_status_fetcher_->trajectory_logging())->has_y());
 }
 
+class DrivetrainBackwardsParamTest
+    : public DrivetrainTest,
+      public ::testing::WithParamInterface<bool> {};
+
 // Tests that simple spline converges when it doesn't start where it thinks.
-TEST_F(DrivetrainTest, SplineOffset) {
+TEST_P(DrivetrainBackwardsParamTest, SplineOffset) {
   SetEnabled(true);
+  if (GetParam()) {
+    // Turn the robot around if we are backwards.
+    (*drivetrain_plant_.mutable_state())(2) += M_PI;
+
+    auto builder = localizer_control_sender_.MakeBuilder();
+    LocalizerControl::Builder localizer_control_builder =
+        builder.MakeBuilder<LocalizerControl>();
+    localizer_control_builder.add_x(drivetrain_plant_.state()(0));
+    localizer_control_builder.add_y(drivetrain_plant_.state()(1));
+    localizer_control_builder.add_theta(drivetrain_plant_.state()(2));
+    ASSERT_TRUE(builder.Send(localizer_control_builder.Finish()));
+  }
   {
     auto builder = trajectory_goal_sender_.MakeBuilder();
 
@@ -834,7 +850,7 @@
 
     SplineGoal::Builder spline_goal_builder = builder.MakeBuilder<SplineGoal>();
     spline_goal_builder.add_spline_idx(1);
-    spline_goal_builder.add_drive_spline_backwards(false);
+    spline_goal_builder.add_drive_spline_backwards(GetParam());
     spline_goal_builder.add_spline(multispline_offset);
     ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
   }
@@ -852,6 +868,10 @@
   VerifyNearSplineGoal();
 }
 
+INSTANTIATE_TEST_CASE_P(DriveSplinesForwardsAndBackwards,
+                        DrivetrainBackwardsParamTest,
+                        ::testing::Values(false, true));
+
 // Tests that simple spline converges when it starts to the side of where it
 // thinks.
 TEST_F(DrivetrainTest, SplineSideOffset) {
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.cc b/frc971/control_loops/drivetrain/splinedrivetrain.cc
index 1ebda6c..629150c 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.cc
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.cc
@@ -134,7 +134,8 @@
     ::Eigen::Matrix<double, 2, 5> K =
         current_trajectory().GainForDistance(current_distance);
     ::Eigen::Matrix<double, 5, 1> goal_state = CurrentGoalState();
-    if (current_trajectory().drive_spline_backwards()) {
+    const bool backwards = current_trajectory().drive_spline_backwards();
+    if (backwards) {
       ::Eigen::Matrix<double, 2, 1> swapU(U_ff(1, 0), U_ff(0, 0));
       U_ff = -swapU;
       goal_state(2, 0) += M_PI;
@@ -145,13 +146,19 @@
     }
     const Eigen::Matrix<double, 5, 1> relative_goal =
         current_trajectory().StateToPathRelativeState(current_distance,
-                                                      goal_state);
+                                                      goal_state, backwards);
     const Eigen::Matrix<double, 5, 1> relative_state =
-        current_trajectory().StateToPathRelativeState(current_distance, state);
+        current_trajectory().StateToPathRelativeState(current_distance, state,
+                                                      backwards);
     Eigen::Matrix<double, 5, 1> state_error = relative_goal - relative_state;
     state_error(2, 0) = ::aos::math::NormalizeAngle(state_error(2, 0));
     ::Eigen::Matrix<double, 2, 1> U_fb = K * state_error;
 
+    if (backwards) {
+      Eigen::Matrix<double, 2, 1> swapU(U_fb(1), U_fb(0));
+      U_fb = -swapU;
+    }
+
     ::Eigen::Matrix<double, 2, 1> xv_state = current_xva_.block<2, 1>(0, 0);
     next_xva_ = current_trajectory().GetNextXVA(dt_config_.dt, &xv_state);
     next_U_ = U_ff + U_fb - voltage_error;
@@ -201,11 +208,17 @@
     ::Eigen::Matrix<double, 5, 1> goal_state = CurrentGoalState();
     trajectory_logging_builder.add_x(goal_state(0));
     trajectory_logging_builder.add_y(goal_state(1));
-    trajectory_logging_builder.add_theta(::aos::math::NormalizeAngle(
-        goal_state(2) +
-        (current_trajectory().drive_spline_backwards() ? M_PI : 0.0)));
-    trajectory_logging_builder.add_left_velocity(goal_state(3));
-    trajectory_logging_builder.add_right_velocity(goal_state(4));
+    if (current_trajectory().drive_spline_backwards()) {
+      trajectory_logging_builder.add_left_velocity(-goal_state(4));
+      trajectory_logging_builder.add_right_velocity(-goal_state(3));
+      trajectory_logging_builder.add_theta(
+          ::aos::math::NormalizeAngle(goal_state(2) + M_PI));
+    } else {
+      trajectory_logging_builder.add_theta(
+          ::aos::math::NormalizeAngle(goal_state(2)));
+      trajectory_logging_builder.add_left_velocity(goal_state(3));
+      trajectory_logging_builder.add_right_velocity(goal_state(4));
+    }
   }
   trajectory_logging_builder.add_is_executing(!IsAtEnd() &&
                                               executing_spline_);
diff --git a/frc971/control_loops/drivetrain/trajectory.cc b/frc971/control_loops/drivetrain/trajectory.cc
index 08dd3fd..c92a81b 100644
--- a/frc971/control_loops/drivetrain/trajectory.cc
+++ b/frc971/control_loops/drivetrain/trajectory.cc
@@ -2,6 +2,7 @@
 
 #include <chrono>
 
+#include "aos/util/math.h"
 #include "Eigen/Dense"
 #include "frc971/control_loops/c2d.h"
 #include "frc971/control_loops/dlqr.h"
@@ -111,7 +112,7 @@
       spline_(std::move(input_spline)),
       config_(config),
       plan_(num_distance == 0
-                ? std::max(100, static_cast<int>(spline_.length() / 0.0025))
+                ? std::max(10000, static_cast<int>(spline_.length() / 0.0025))
                 : num_distance,
             vmax),
       plan_segment_type_(plan_.size(),
@@ -711,7 +712,8 @@
 }
 
 Eigen::Matrix<double, 5, 1> FinishedTrajectory::StateToPathRelativeState(
-    double distance, const Eigen::Matrix<double, 5, 1> &state) const {
+    double distance, const Eigen::Matrix<double, 5, 1> &state,
+    bool drive_backwards) const {
   const double nominal_theta = spline().Theta(distance);
   const Eigen::Matrix<double, 2, 1> nominal_xy = spline().XY(distance);
   const Eigen::Matrix<double, 2, 1> xy_err =
@@ -721,9 +723,16 @@
   Eigen::Matrix<double, 5, 1> path_state;
   path_state(0) = distance + xy_err.x() * ctheta + xy_err.y() * stheta;
   path_state(1) = -xy_err.x() * stheta + xy_err.y() * ctheta;
-  path_state(2) = state(2) - nominal_theta;
+  path_state(2) = aos::math::NormalizeAngle(state(2) - nominal_theta +
+                                            (drive_backwards ? M_PI : 0.0));
+  path_state(2) = aos::math::NormalizeAngle(state(2) - nominal_theta);
   path_state(3) = state(3);
   path_state(4) = state(4);
+  if (drive_backwards) {
+    std::swap(path_state(3), path_state(4));
+    path_state(3) *= -1.0;
+    path_state(4) *= -1.0;
+  }
   return path_state;
 }
 
diff --git a/frc971/control_loops/drivetrain/trajectory.h b/frc971/control_loops/drivetrain/trajectory.h
index 00b37f6..60695de 100644
--- a/frc971/control_loops/drivetrain/trajectory.h
+++ b/frc971/control_loops/drivetrain/trajectory.h
@@ -206,7 +206,8 @@
   // point (i.e., distance should be roughly equal to the actual distance along
   // the path).
   Eigen::Matrix<double, 5, 1> StateToPathRelativeState(
-      double distance, const Eigen::Matrix<double, 5, 1> &state) const;
+      double distance, const Eigen::Matrix<double, 5, 1> &state,
+      bool drive_backwards) const;
 
   // Retrieves the gain matrix K for a given distance along the path.
   Eigen::Matrix<double, 2, 5> GainForDistance(double distance) const;
diff --git a/frc971/control_loops/drivetrain/trajectory_test.cc b/frc971/control_loops/drivetrain/trajectory_test.cc
index c2f6655..c13d844 100644
--- a/frc971/control_loops/drivetrain/trajectory_test.cc
+++ b/frc971/control_loops/drivetrain/trajectory_test.cc
@@ -453,8 +453,8 @@
     const Eigen::Matrix<double, 5, 1> goal_absolute_state =
         finished_trajectory_->GoalState(distance, velocity);
     const Eigen::Matrix<double, 5, 1> goal_relative_state =
-        finished_trajectory_->StateToPathRelativeState(distance,
-                                                       goal_absolute_state);
+        finished_trajectory_->StateToPathRelativeState(
+            distance, goal_absolute_state, false);
     ASSERT_EQ(distance, goal_relative_state(0));
     ASSERT_EQ(0.0, goal_relative_state(1));
     ASSERT_NEAR(goal_absolute_state(2), goal_relative_state(2), 1e-2);
@@ -485,11 +485,11 @@
     const Eigen::Matrix<double, 5, 1> goal_absolute_state =
         finished_trajectory_->GoalState(distance, velocity);
     const Eigen::Matrix<double, 5, 1> goal_relative_state =
-        finished_trajectory_->StateToPathRelativeState(distance,
-                                                       goal_absolute_state);
+        finished_trajectory_->StateToPathRelativeState(
+            distance, goal_absolute_state, false);
     const Eigen::Matrix<double, 5, 1> current_relative_state =
-        finished_trajectory_->StateToPathRelativeState(distance,
-                                                       absolute_state);
+        finished_trajectory_->StateToPathRelativeState(distance, absolute_state,
+                                                       false);
 
     const Eigen::Matrix<double, 2, 1> U_ff =
         finished_trajectory_->FFVoltage(distance);
diff --git a/y2020/actors/autonomous_actor.cc b/y2020/actors/autonomous_actor.cc
index 2e0bebc..c78a33f 100644
--- a/y2020/actors/autonomous_actor.cc
+++ b/y2020/actors/autonomous_actor.cc
@@ -11,8 +11,9 @@
 #include "y2020/actors/auto_splines.h"
 #include "y2020/control_loops/drivetrain/drivetrain_base.h"
 
-DEFINE_bool(spline_auto, true, "If true, define a spline autonomous mode");
-DEFINE_bool(galactic_search, false,
+DEFINE_bool(spline_auto, false, "If true, define a spline autonomous mode");
+DEFINE_bool(ignore_vision, true, "If true, ignore vision");
+DEFINE_bool(galactic_search, true,
             "If true, do the galactic search autonomous");
 DEFINE_bool(bounce, false, "If true, run the AutoNav Bounce autonomous");
 DEFINE_bool(barrel, false, "If true, run the AutoNav Barrel autonomous");
@@ -157,13 +158,12 @@
   CHECK(galactic_search_splines_);
 
   path_fetcher_.Fetch();
-  CHECK(path_fetcher_.get() != nullptr)
-      << "Expect at least one GalacticSearchPath message before running "
-         "auto...";
-  if (path_fetcher_->alliance() == y2020::vision::Alliance::kUnknown) {
-    AOS_LOG(ERROR, "The galactic search path is unknown, doing nothing.");
-  } else {
-    SplineHandle *spline = nullptr;
+  SplineHandle *spline = nullptr;
+  if (path_fetcher_.get()) {
+    if (path_fetcher_->alliance() == y2020::vision::Alliance::kUnknown) {
+      AOS_LOG(ERROR, "The galactic search path is unknown, doing nothing.");
+      return;
+    }
     if (path_fetcher_->alliance() == y2020::vision::Alliance::kRed) {
       if (path_fetcher_->letter() == y2020::vision::Letter::kA) {
         LOG(INFO) << "Red A";
@@ -180,23 +180,30 @@
       } else {
         LOG(INFO) << "Blue B";
         CHECK(path_fetcher_->letter() == y2020::vision::Letter::kB);
-        spline = &galactic_search_splines_->red_b;
+        spline = &galactic_search_splines_->blue_b;
       }
     }
-    CHECK_NOTNULL(spline);
-
-    SendStartingPosition(spline->starting_position());
-
-    set_intake_goal(1.2);
-    set_roller_voltage(7.0);
-    SendSuperstructureGoal();
-
-    if (!spline->WaitForPlan()) return;
-    spline->Start();
-
-    if (!spline->WaitForSplineDistanceRemaining(0.02)) return;
-    RetractIntake();
   }
+  if (FLAGS_ignore_vision) {
+    LOG(INFO) << "Forcing Red B";
+    spline = &galactic_search_splines_->red_b;
+  }
+
+  CHECK(spline != nullptr)
+      << "Expect at least one GalacticSearchPath message before running "
+         "auto...";
+
+  SendStartingPosition(spline->starting_position());
+
+  set_intake_goal(1.25);
+  set_roller_voltage(12.0);
+  SendSuperstructureGoal();
+
+  if (!spline->WaitForPlan()) return;
+  spline->Start();
+
+  if (!spline->WaitForSplineDistanceRemaining(0.02)) return;
+  RetractIntake();
 }
 
 void AutonomousActor::AutoNavBounce() {
@@ -288,8 +295,8 @@
 
     frc971::ProfileParameters::Builder profile_params_builder =
         builder.MakeBuilder<frc971::ProfileParameters>();
-    profile_params_builder.add_max_velocity(10.0);
-    profile_params_builder.add_max_acceleration(30.0);
+    profile_params_builder.add_max_velocity(20.0);
+    profile_params_builder.add_max_acceleration(60.0);
     flatbuffers::Offset<frc971::ProfileParameters> profile_params_offset =
         profile_params_builder.Finish();
     intake_builder.add_unsafe_goal(intake_goal_);
diff --git a/y2020/actors/splines/autonav_barrel.json b/y2020/actors/splines/autonav_barrel.json
index eab3cfc..2649661 100644
--- a/y2020/actors/splines/autonav_barrel.json
+++ b/y2020/actors/splines/autonav_barrel.json
@@ -1 +1 @@
-{"spline_count": 4, "spline_x": [-3.5151586543642246, -1.265622652236729, -2.258167110671239, 1.0300078526327052, 0.25745854323814665, -0.7822290779903016, -1.8219166992187499, -3.1287426322810883, 1.6738468981570327, 3.5446208496093754, 2.9234051993534482, 2.302189549097521, -0.8110157028666762, 3.38275119440928, 4.28405580452697, 4.453499428108947, 4.622943051690925, 4.06052568873719, 2.755791372575431, -0.025793453663793216, -3.4092430664062503], "spline_y": [-0.018909511382004314, -0.07759003939693922, -0.32922657858767934, 0.6189274969231588, -1.5383952720905172, -1.337796770608836, -1.137198269127155, 1.4213215028498833, -1.7862918411708972, 0.2754524444162029, 1.0503166436557112, 1.8251808428952194, 1.3131649557871359, -2.1388633405610635, -1.6289002551771192, -1.028790341729987, -0.4286804282828549, 0.2615763132274651, 0.013016687432650737, 0.35339494881465516, 0.2666422649515086], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 6.0}]}
+{"spline_count": 4, "spline_x": [-3.439527264404297, -1.4521381072998047, -1.9621627899169916, 2.3140273590087896, -0.15155005187988285, -1.2099180084228516, -2.2682859649658202, -1.9194444671630853, 2.2364890686035164, 3.0541333465576175, 2.1377636993408204, 1.2213940521240234, -1.428989520263672, 1.0701125885009766, 3.340432150268555, 3.8391586853027344, 4.337885220336914, 3.065018728637696, 2.9864502685546874, 0.33045889892578123, -3.72018571472168], "spline_y": [0.0026085617065429684, -0.004877609252929687, -0.094301220703125, 0.4880167236328125, -1.993748071289062, -1.4883794998168944, -0.9830109283447268, 2.509491009521483, -2.4357923103332517, 0.09796495056152343, 1.1720165428161622, 2.246068135070801, 1.8604140586853029, -2.8892405044555662, -2.3678153549194336, -1.3137169052124023, -0.2596184555053709, 1.3271532943725592, -0.6553675552368162, -0.01534266815185547, -0.04329328765869141], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 7.499999999999998}, {"constraint_type": "LATERAL_ACCELERATION", "value": 8.499999999999995}, {"constraint_type": "VOLTAGE", "value": 11.999999999999993}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/autonav_bounce_1.json b/y2020/actors/splines/autonav_bounce_1.json
index 339900b..233040c 100644
--- a/y2020/actors/splines/autonav_bounce_1.json
+++ b/y2020/actors/splines/autonav_bounce_1.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [-3.841487603305785, -3.3755947873443977, -3.0957801579518933, -2.3949857243581434, -2.3116481497990145, -2.304892561983471], "spline_y": [0.0503801652892562, 0.05652844187629669, 0.11639432357851401, 0.3335849649896266, 0.9762657982284103, 1.5617851239669422], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
+{"spline_count": 1, "spline_x": [-3.854933303833008, -3.1908587219238282, -2.8742285649343122, -2.3949857243581434, -2.3116481497990145, -2.304892561983471], "spline_y": [0.04259449310302734, 0.04866970367431641, 0.12185038589540864, 0.3335849649896266, 0.9762657982284103, 1.5617851239669422], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 9.999999999999993}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/autonav_bounce_2.json b/y2020/actors/splines/autonav_bounce_2.json
index 127128e..365f721 100644
--- a/y2020/actors/splines/autonav_bounce_2.json
+++ b/y2020/actors/splines/autonav_bounce_2.json
@@ -1 +1 @@
-{"spline_count": 2, "spline_x": [-2.300972622575431, -2.276803448275862, -2.2713968817349137, -1.6818424905711238, -1.7119211678340525, -1.5873674232219828, -1.462813678609913, -1.183627512122845, 0.07931769261853441, 0.20563043170797451, -0.0033345198006461863], "spline_y": [1.52789615352236, 0.9051463547279094, 0.30167396787446127, -0.15916462318157443, -0.3509412092537718, -0.7144320935479526, -1.0779229778421333, -1.6131281603582976, -2.2125802633351292, -1.0379113062365304, 1.5787289769665949], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
+{"spline_count": 2, "spline_x": [-2.300972622575431, -2.276803448275862, -2.2197493927001952, -2.0912932800292934, -1.8907473815917966, -1.6507643554687499, -1.4107813293457032, -1.1313611755371065, -0.17296153564453126, -0.002871917724609375, -0.0033345198006461863], "spline_y": [1.52789615352236, 0.9051463547279094, 0.5131617004394531, 0.6903293746948247, 0.10570575714111341, -0.4938134628295899, -1.0933326828002932, -1.7077475051879882, -2.25593497467041, -1.0112510650634765, 1.5787289769665949], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 5.0}, {"constraint_type": "VOLTAGE", "value": 9.999999999999993}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/autonav_bounce_3.json b/y2020/actors/splines/autonav_bounce_3.json
index 6636c41..96a3e83 100644
--- a/y2020/actors/splines/autonav_bounce_3.json
+++ b/y2020/actors/splines/autonav_bounce_3.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [0.012595041322314211, -0.1130877609569499, -0.17110139636281083, 2.5749025625648345, 2.4596194323781124, 2.304892561983471], "spline_y": [1.5869752066115703, -1.207064795529694, -2.512129978037474, -2.7245033896038637, -1.2752370311689574, 1.536595041322314], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [0.012595041322314211, 0.035615267944335935, -1.0700335235595704, 3.6841669830322266, 2.4339549224853516, 2.4026312530517577], "spline_y": [1.5869752066115703, -0.6927920150756836, -2.8280890045166016, -2.13918454284668, -0.8389284439086915, 1.5275657707214354], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 5.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 5.5}, {"constraint_type": "VOLTAGE", "value": 9.999999999999993}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/autonav_bounce_4.json b/y2020/actors/splines/autonav_bounce_4.json
index 2f3a0e6..042b800 100644
--- a/y2020/actors/splines/autonav_bounce_4.json
+++ b/y2020/actors/splines/autonav_bounce_4.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [2.2545123966942158, 2.2545123966942158, 2.3716765227891603, 2.7544087339535794, 3.0050034929330915, 3.765917355371901], "spline_y": [1.536595041322314, 0.9572231404958678, 0.689289587250389, 0.2103741125842842, 0.05097942228831691, 0.0503801652892562], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [2.420588296508789, 2.4232765045166014, 2.5394848846055655, 2.5435332334653036, 2.696887710571289, 3.661613708496094], "spline_y": [1.5176544570922852, 0.9584327774047853, 0.7181724172979964, 0.2998157461902411, 0.1163405731201172, 0.12068274993896484], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 5.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 5.5}, {"constraint_type": "VOLTAGE", "value": 9.999999999999993}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/autonav_slalom.json b/y2020/actors/splines/autonav_slalom.json
index 5d878e6..6936d80 100644
--- a/y2020/actors/splines/autonav_slalom.json
+++ b/y2020/actors/splines/autonav_slalom.json
@@ -1 +1 @@
-{"spline_count": 8, "spline_x": [-3.4207588741571575, -3.1903979471926864, -3.084489136248705, -2.732087602924013, -2.5142798033908194, -2.273429890106328, -2.0325799768218364, -1.768687949786047, -1.0683327444242738, -0.5380152157352175, 0.016462181502852943, 0.5709395787409234, 1.149576844528008, 1.6589843304266054, 2.0281691681794594, 2.3269663308804454, 2.6257634935814314, 2.8541729812305494, 3.1768999773080915, 3.664860157060426, 3.681661987811204, 3.698463818561982, 3.244107300311203, 2.6816450580264526, 2.6105688213174276, 2.3169760114107887, 2.0233832015041497, 1.5072738183998968, 0.5446569023923764, 0.2191818351270748, -0.09625968458246914, -0.41170120429201307, -0.7171091764457993, -1.6306328813861517, -1.9163118638161307, -2.2553543746758296, -2.594396885535528, -2.9868029248249472, -3.27459853961359, -3.6931884481976143, -4.068067814363978], "spline_y": [-1.504634589357495, -1.4374380733759078, -1.3291470861157937, -1.2507240045951113, -1.0273675714389912, -0.758464560101141, -0.48956154876329094, -0.17511195924371137, 0.230135523372666, 0.2566930068399896, 0.2366884380672977, 0.2166838692946058, 0.15011724828189843, -0.0019051235088172191, -0.4611302049565611, -0.8345066232008558, -1.2078830414451505, -1.495410796485996, -1.6395803232786565, -1.2497401796712917, -0.784383657368387, -0.3190271350654823, 0.22184576593296246, -0.04691945588044605, -0.3698101011410789, -0.7732763550311204, -1.176742608921162, -1.6607844714406121, -1.6312071973871891, -1.6388462177450727, -1.623608317394969, -1.6083704170448652, -1.570255595986774, -1.4706935943983404, -1.1535808460029824, -0.7902526419865145, -0.42692443797004653, -0.01738077833246887, 0.01122347781865923, 0.025194254894968883, 0.028633203530212654], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
+{"spline_count": 8, "spline_x": [-3.4749518463134765, -3.1365934295654294, -2.9590075597612686, -2.760017578125, -2.5225692810058593, -2.273429890106328, -2.0242904992067965, -1.7634600145268742, -1.4530334014892579, -1.1285066986083985, -0.68847890625, -0.24845111389160157, 0.30707776794433594, 1.871516759595437, 2.184855541688278, 2.417896609990923, 2.650937678293568, 2.8036810328060167, 3.5928316545035397, 3.8742948612577215, 3.853217129516602, 3.832139397775482, 3.5085207275390626, 2.5905665683350616, 2.4835600727761933, 2.3169760114107887, 2.150391950045384, 1.9242303228734432, 1.4789411224365234, 1.0076788024902341, 0.21033948669433594, -0.5869998291015622, -1.7104161407470695, -1.6109939147949213, -2.028241729609699, -2.2553543746758296, -2.4824670197419603, -2.519444495059444, -3.4609283874195165, -3.690070111083984, -4.450609153747559], "spline_y": [-1.6666796630859375, -1.5026007247924806, -1.3657751963192004, -1.3422337692260742, -1.0754058700561524, -0.758464560101141, -0.4415232501461297, -0.07446852940602877, 0.20931454925537119, 0.2820978973388672, 0.3545516143798828, 0.4270053314208984, 0.49912941741943356, 0.32144404823651485, -0.1969548795707987, -0.7699543538073782, -1.3429538280439577, -1.970553848709803, -1.7554159149993005, -1.2416998867240683, -0.7131605392456054, -0.18462119176714253, 0.3587414749145508, 0.459862695717713, -0.20117116182572614, -0.7732763550311204, -1.3453815482365146, -1.8285580771038639, -1.8799707138061523, -2.1832105377197277, -2.2168379425048825, -2.2504653472900373, -2.0144803329467713, -1.7455779479980467, -1.3180884153753891, -0.7902526419865145, -0.2624168685976398, 0.365765145557452, 1.047112901958292, 1.014591268157959, 1.6061016746520995], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.999999999999993}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.999999999999993}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/spline_blue_a.json b/y2020/actors/splines/spline_blue_a.json
index 063a27b..27b72b3 100644
--- a/y2020/actors/splines/spline_blue_a.json
+++ b/y2020/actors/splines/spline_blue_a.json
@@ -1 +1 @@
-{"spline_count": 3, "spline_x": [-3.8589564582257236, -2.706301079868285, -1.8662093637009298, -1.3063849916064052, -0.4873721348786154, -0.00625139624225228, 0.4748693423941108, 0.6180979629390473, -0.009563129519629676, 0.15372038836518587, 0.6260651875645665, 1.0984099867639472, 1.879816067277893, 2.9980503292871896, 3.5245728709323347, 4.3991472026730385], "spline_y": [-1.6780186596074382, -1.8082232817342458, -1.892411108600207, -1.749871279377583, -1.9347886872094529, -1.488971578802944, -1.0431544703964353, 0.03339715424845213, -0.09653840876807873, 0.6210084137719525, 0.8305055244382749, 1.0400026351045972, 0.7414500338972108, -0.9412994536092459, -1.2421690381262913, -1.7536811563791324], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
+{"spline_count": 3, "spline_x": [-3.368782745361328, -2.2354461090087887, -1.4045700997849144, -1.7840407197558215, -0.9349464202880862, -0.4274192596435547, 0.08010790100097676, 0.24606792282230439, -0.7738946228027348, -0.3780420410156249, 0.16000186157226565, 0.6980457641601562, 1.3782809875488273, 2.5139577847315264, 3.0543124053955077, 4.539442684936523], "spline_y": [-1.5853468368530275, -1.5885472229003905, -1.6684259431949335, -2.030274512714982, -2.168715298461914, -1.8642716720581054, -1.5598280456542968, -0.8125000070997483, -0.2118207916259753, 0.4719089859008792, 0.7151854156494141, 0.958461845397949, 0.7612849273681641, 0.032713186771613084, -0.2212173110961914, -0.32124376373291014], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.500000000000002}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.5}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/spline_blue_b.json b/y2020/actors/splines/spline_blue_b.json
index fb78187..00c5165 100644
--- a/y2020/actors/splines/spline_blue_b.json
+++ b/y2020/actors/splines/spline_blue_b.json
@@ -1 +1 @@
-{"spline_count": 3, "spline_x": [-4.150494304057981, -3.3986216889688787, -2.2755236069860536, -0.7710065615315085, -0.3059309707515497, 0.07081943278667355, 0.4475698363248968, 0.7359950526213844, 0.6477528893336757, 0.9985598447184914, 1.5433015318310954, 2.0880432189436995, 2.826719637784092, 2.54224882166839, 3.098134168388431, 4.279168364217459], "spline_y": [-1.8370325937822833, -1.7225587047230115, -1.4951960691341684, -1.2591343681398501, -1.052224068633781, -0.746549088407154, -0.44087410818052697, -0.03643444723334266, 0.4353676213035902, 0.7416545188210228, 0.7718694725351886, 0.8020844262493543, 0.5562274361602532, -0.9685113232825411, -0.8008121610278923, -1.6595312237700157], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
+{"spline_count": 3, "spline_x": [-3.39804026184082, -2.5546545318603515, -1.435279833984375, -0.8065054229736328, -0.3800140136718751, -0.1415320587158203, 0.09694989624023448, 0.14742239685058633, 0.03417698364257811, 0.5247121582031249, 1.0381308197021484, 1.5515494812011719, 2.0878516296386724, 2.627104107312922, 3.1052011596679687, 4.269367309570312], "spline_y": [-1.5841195861816406, -1.5982576766967775, -1.4621136611938477, -1.5811784866333012, -1.4247781494140626, -1.0768819427490233, -0.728985736083984, -0.18959365997314404, 0.6665802429199222, 0.8889393447875978, 0.8239869140625, 0.7590344833374022, 0.40677052001953085, -1.0101512234900605, -0.8171425643920898, -1.7796634643554687], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/spline_red_a.json b/y2020/actors/splines/spline_red_a.json
index eae42c9..2e91d4f 100644
--- a/y2020/actors/splines/spline_red_a.json
+++ b/y2020/actors/splines/spline_red_a.json
@@ -1 +1 @@
-{"spline_count": 3, "spline_x": [-3.5430995125258264, -2.833856622869318, -2.2671351126678716, -1.5517361505681804, -1.0942218895273754, -0.7058266076962806, -0.3174313258651858, 0.0018449767561987526, -0.7213536245803214, -0.46077833241864685, 0.08654170971074387, 0.6338617518401346, 1.4679265439372415, 1.8681219896048553, 2.4377923876549588, 4.128750484245868], "spline_y": [1.345144878292872, 0.563397477079029, -0.10274521807205578, -0.6578218499806299, -0.8755060450025827, -0.6711287448347107, -0.4667514446668389, 0.15968735069085743, 0.5673580271823342, 1.1876484375, 1.4852908501743287, 1.7829332628486574, 1.7579276778796489, 1.8390174812758264, 1.9139266125387395, 1.8437913586324897], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
+{"spline_count": 3, "spline_x": [-3.251309683227539, -2.471539837646484, -1.9919760864257812, -1.8171762908935547, -1.2402998748779297, -0.9586693908691406, -0.6770389068603515, -0.6906543548583981, -0.8745954528808596, -0.8974987060546875, -0.6056990753173828, -0.313899444580078, 0.2926030700683593, 1.7207530778616913, 2.3043570190429685, 4.025684509277344], "spline_y": [0.9793806266784668, 0.18692638092041014, -0.29821900634765625, -1.2191290740966798, -1.1123914031982423, -0.7905331420898437, -0.46867488098144516, 0.06830397033691415, 0.41884652709960957, 0.8500789260864258, 1.2572325622558593, 1.664386198425293, 2.047461071777344, 1.5242765182936486, 1.6542623977661133, 1.652634299468994], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.5}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2020/actors/splines/spline_red_b.json b/y2020/actors/splines/spline_red_b.json
index ace02fe..28a8451 100644
--- a/y2020/actors/splines/spline_red_b.json
+++ b/y2020/actors/splines/spline_red_b.json
@@ -1 +1 @@
-{"spline_count": 2, "spline_x": [-3.392645926339286, -2.154575892857143, -1.9643174545865811, -1.8674530715821605, -1.4586490399672885, -0.7749665868973982, -0.09128413382750789, 0.8672767406974007, 0.3081139946408683, 0.39452214556653653, 4.533722882231405], "spline_y": [1.5839347098214285, 0.8960059988839286, 0.540389038357809, -0.3293477472090389, -0.755995497807628, -0.7561097332951151, -0.7562239687826022, -0.3298046891589874, 1.1545971581813754, 1.2564632146958519, 1.674700392037384], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 2.0}]}
+{"spline_count": 2, "spline_x": [-3.240201058959961, -2.4673773010253908, -2.0606439880371092, -2.3827150268554687, -1.8442327789306632, -1.3579938537597656, -0.8717549285888679, -0.43775932617187774, 0.2918380004882813, 0.4791974945068359, 4.533722882231405], "spline_y": [1.6369277000427247, 0.9154947006225586, 0.668192935180664, -0.5594466659545898, -1.08513957824707, -1.0174198745727538, -0.9497001708984376, -0.28856785125732465, 0.613231755065918, 1.6393723182678221, 1.674700392037384], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 6.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 6.0}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2020/y2020_roborio.json b/y2020/y2020_roborio.json
index 7a4453a..82eee24 100644
--- a/y2020/y2020_roborio.json
+++ b/y2020/y2020_roborio.json
@@ -211,8 +211,8 @@
       "name": "/drivetrain",
       "type": "frc971.control_loops.drivetrain.fb.Trajectory",
       "source_node": "roborio",
-      "max_size": 400000,
-      "frequency": 2,
+      "max_size": 600000,
+      "frequency": 4,
       "num_senders": 2,
       "read_method": "PIN",
       "num_readers": 6