Merge "Add time-of-flight data to debugging webpage."
diff --git a/WORKSPACE b/WORKSPACE
index f411682..376b91d 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -580,6 +580,13 @@
     urls = ["https://www.frc971.org/Build-Dependencies/test_image_frc971.vision.CameraImage_2023.01.28.tar.gz"],
 )
 
+http_file(
+    name = "game_pieces_edgetpu_model",
+    downloaded_file_path = "edgetpu_model.tflite",
+    sha256 = "3d37f34805d017153064076519aaf4b532658a3b8f2518bce8787f27a5c3064c",
+    urls = ["https://www.frc971.org/Build-Dependencies/models/2023/model_edgetpu_2023.04.09_3.tflite"],
+)
+
 # Recompressed from libusb-1.0.21.7z.
 http_file(
     name = "libusb_1_0_windows",
@@ -1567,17 +1574,17 @@
 http_archive(
     name = "libedgetpu",
     build_file = "//third_party:libedgetpu/libedgetpu.BUILD",
-    sha256 = "d082df79a33309f58da697cce258acca96ceb12db40660fdbf7826289e4a037c",
+    sha256 = "c900faf2c9ea9599fda60c3d03ac43d0d7b34119659c9e35638b81cd14354b57",
     strip_prefix = "libedgetpu-bazel",
-    url = "https://www.frc971.org/Build-Dependencies/libedgetpu-1.0.tar.gz",
+    url = "https://www.frc971.org/Build-Dependencies/libedgetpu-ddfa7bde33c23afd8c2892182faa3e5b4e6ad94e.tar.gz",
 )
 
 http_archive(
     name = "libtensorflowlite",
     build_file = "//third_party:libtensorflowlite/libtensorflowlite.BUILD",
-    sha256 = "0e3f8deac9c7cdf9aa5812ad6a87af318ed1cf08cb0c414aa494846b7fc15302",
+    sha256 = "a073dfddb3cb25113ba7eac6edb5569d0ae7988cad881d3f665e8ca0b8b85108",
     strip_prefix = "tensorflow-bazel",
-    url = "https://www.frc971.org/Build-Dependencies/tensorflow-2.8.0.tar.gz",
+    url = "https://www.frc971.org/Build-Dependencies/tensorflow-a4dfb8d1a71385bd6d122e4f27f86dcebb96712d.tar.gz",
 )
 
 http_archive(
diff --git a/aos/events/logging/log_reader.cc b/aos/events/logging/log_reader.cc
index fa5e5d5..0af69c7 100644
--- a/aos/events/logging/log_reader.cc
+++ b/aos/events/logging/log_reader.cc
@@ -1331,45 +1331,8 @@
                                    std::string_view add_prefix,
                                    std::string_view new_type,
                                    RemapConflict conflict_handling) {
-  if (replay_channels_ != nullptr) {
-    CHECK(std::find(replay_channels_->begin(), replay_channels_->end(),
-                    std::make_pair(std::string{name}, std::string{type})) !=
-          replay_channels_->end())
-        << "Attempted to remap channel " << name << " " << type
-        << " which is not included in the replay channels passed to LogReader.";
-  }
-
-  for (size_t ii = 0; ii < logged_configuration()->channels()->size(); ++ii) {
-    const Channel *const channel = logged_configuration()->channels()->Get(ii);
-    if (channel->name()->str() == name &&
-        channel->type()->string_view() == type) {
-      CHECK_EQ(0u, remapped_channels_.count(ii))
-          << "Already remapped channel "
-          << configuration::CleanedChannelToString(channel);
-      RemappedChannel remapped_channel;
-      remapped_channel.remapped_name =
-          std::string(add_prefix) + std::string(name);
-      remapped_channel.new_type = new_type;
-      const std::string_view remapped_type =
-          remapped_channel.new_type.empty() ? type : remapped_channel.new_type;
-      CheckAndHandleRemapConflict(
-          remapped_channel.remapped_name, remapped_type,
-          remapped_configuration_, conflict_handling,
-          [this, &remapped_channel, remapped_type, add_prefix,
-           conflict_handling]() {
-            RemapLoggedChannel(remapped_channel.remapped_name, remapped_type,
-                               add_prefix, "", conflict_handling);
-          });
-      remapped_channels_[ii] = std::move(remapped_channel);
-      VLOG(1) << "Remapping channel "
-              << configuration::CleanedChannelToString(channel)
-              << " to have name " << remapped_channels_[ii].remapped_name;
-      MakeRemappedConfig();
-      return;
-    }
-  }
-  LOG(FATAL) << "Unabled to locate channel with name " << name << " and type "
-             << type;
+  RemapLoggedChannel(name, type, nullptr, add_prefix, new_type,
+                     conflict_handling);
 }
 
 void LogReader::RemapLoggedChannel(std::string_view name, std::string_view type,
@@ -1377,7 +1340,16 @@
                                    std::string_view add_prefix,
                                    std::string_view new_type,
                                    RemapConflict conflict_handling) {
-  VLOG(1) << "Node is " << aos::FlatbufferToJson(node);
+  if (node != nullptr) {
+    VLOG(1) << "Node is " << aos::FlatbufferToJson(node);
+  }
+  if (replay_channels_ != nullptr) {
+    CHECK(std::find(replay_channels_->begin(), replay_channels_->end(),
+                    std::make_pair(std::string{name}, std::string{type})) !=
+          replay_channels_->end())
+        << "Attempted to remap channel " << name << " " << type
+        << " which is not included in the replay channels passed to LogReader.";
+  }
   const Channel *remapped_channel =
       configuration::GetChannel(logged_configuration(), name, type, "", node);
   CHECK(remapped_channel != nullptr) << ": Failed to find {\"name\": \"" << name
@@ -1408,6 +1380,7 @@
     maps_.emplace_back(std::move(new_map));
   }
 
+  // Then remap the logged channel to the prefixed channel.
   const size_t channel_index =
       configuration::ChannelIndex(logged_configuration(), remapped_channel);
   CHECK_EQ(0u, remapped_channels_.count(channel_index))
@@ -1432,6 +1405,51 @@
   MakeRemappedConfig();
 }
 
+void LogReader::RenameLoggedChannel(const std::string_view name,
+                                    const std::string_view type,
+                                    const std::string_view new_name,
+                                    const std::vector<MapT> &add_maps) {
+  RenameLoggedChannel(name, type, nullptr, new_name, add_maps);
+}
+
+void LogReader::RenameLoggedChannel(const std::string_view name,
+                                    const std::string_view type,
+                                    const Node *const node,
+                                    const std::string_view new_name,
+                                    const std::vector<MapT> &add_maps) {
+  if (node != nullptr) {
+    VLOG(1) << "Node is " << aos::FlatbufferToJson(node);
+  }
+  // First find the channel and rename it.
+  const Channel *remapped_channel =
+      configuration::GetChannel(logged_configuration(), name, type, "", node);
+  CHECK(remapped_channel != nullptr) << ": Failed to find {\"name\": \"" << name
+                                     << "\", \"type\": \"" << type << "\"}";
+  VLOG(1) << "Original {\"name\": \"" << name << "\", \"type\": \"" << type
+          << "\"}";
+  VLOG(1) << "Remapped "
+          << aos::configuration::StrippedChannelToString(remapped_channel);
+
+  const size_t channel_index =
+      configuration::ChannelIndex(logged_configuration(), remapped_channel);
+  CHECK_EQ(0u, remapped_channels_.count(channel_index))
+      << "Already remapped channel "
+      << configuration::CleanedChannelToString(remapped_channel);
+
+  RemappedChannel remapped_channel_struct;
+  remapped_channel_struct.remapped_name = new_name;
+  remapped_channel_struct.new_type.clear();
+  remapped_channels_[channel_index] = std::move(remapped_channel_struct);
+
+  // Then add any provided maps.
+  for (const MapT &map : add_maps) {
+    maps_.push_back(map);
+  }
+
+  // Finally rewrite the config.
+  MakeRemappedConfig();
+}
+
 void LogReader::MakeRemappedConfig() {
   for (std::unique_ptr<State> &state : states_) {
     if (state) {
@@ -1589,20 +1607,26 @@
 
   // Now create the new maps.  These are second so they take effect first.
   for (const MapT &map : maps_) {
+    CHECK(!map.match->name.empty());
     const flatbuffers::Offset<flatbuffers::String> match_name_offset =
         fbb.CreateString(map.match->name);
-    const flatbuffers::Offset<flatbuffers::String> match_type_offset =
-        fbb.CreateString(map.match->type);
-    const flatbuffers::Offset<flatbuffers::String> rename_name_offset =
-        fbb.CreateString(map.rename->name);
+    flatbuffers::Offset<flatbuffers::String> match_type_offset;
+    if (!map.match->type.empty()) {
+      match_type_offset = fbb.CreateString(map.match->type);
+    }
     flatbuffers::Offset<flatbuffers::String> match_source_node_offset;
     if (!map.match->source_node.empty()) {
       match_source_node_offset = fbb.CreateString(map.match->source_node);
     }
+    CHECK(!map.rename->name.empty());
+    const flatbuffers::Offset<flatbuffers::String> rename_name_offset =
+        fbb.CreateString(map.rename->name);
     Channel::Builder match_builder(fbb);
     match_builder.add_name(match_name_offset);
-    match_builder.add_type(match_type_offset);
-    if (!map.match->source_node.empty()) {
+    if (!match_type_offset.IsNull()) {
+      match_builder.add_type(match_type_offset);
+    }
+    if (!match_source_node_offset.IsNull()) {
       match_builder.add_source_node(match_source_node_offset);
     }
     const flatbuffers::Offset<Channel> match_offset = match_builder.Finish();
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index d4936f1..6a0fcea 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -32,8 +32,7 @@
 class EventNotifier;
 
 // Vector of pair of name and type of the channel
-using ReplayChannels =
-    std::vector<std::pair<std::string, std::string>>;
+using ReplayChannels = std::vector<std::pair<std::string, std::string>>;
 // Vector of channel indices
 using ReplayChannelIndices = std::vector<size_t>;
 
@@ -198,7 +197,6 @@
     RemapLoggedChannel(name, T::GetFullyQualifiedName(), add_prefix, new_type,
                        conflict_handling);
   }
-
   // Remaps the provided channel, though this respects node mappings, and
   // preserves them too.  This makes it so if /aos -> /pi1/aos on one node,
   // /original/aos -> /original/pi1/aos on the same node after renaming, just
@@ -221,11 +219,40 @@
                        new_type, conflict_handling);
   }
 
+  // Similar to RemapLoggedChannel(), but lets you specify a name for the new
+  // channel without constraints. This is useful when an application has been
+  // updated to use new channels but you want to support replaying old logs. By
+  // default, this will not add any maps for the new channel. Use add_maps to
+  // specify any maps you'd like added.
+  void RenameLoggedChannel(std::string_view name, std::string_view type,
+                           std::string_view new_name,
+                           const std::vector<MapT> &add_maps = {});
+  template <typename T>
+  void RenameLoggedChannel(std::string_view name, std::string_view new_name,
+                           const std::vector<MapT> &add_maps = {}) {
+    RenameLoggedChannel(name, T::GetFullyQualifiedName(), new_name, add_maps);
+  }
+  // The following overloads are more suitable for multi-node configurations,
+  // and let you rename a channel on a specific node.
+  void RenameLoggedChannel(std::string_view name, std::string_view type,
+                           const Node *node, std::string_view new_name,
+                           const std::vector<MapT> &add_maps = {});
+  template <typename T>
+  void RenameLoggedChannel(std::string_view name, const Node *node,
+                           std::string_view new_name,
+                           const std::vector<MapT> &add_maps = {}) {
+    RenameLoggedChannel(name, T::GetFullyQualifiedName(), node, new_name,
+                        add_maps);
+  }
+
   template <typename T>
   bool HasChannel(std::string_view name, const Node *node = nullptr) {
-    return configuration::GetChannel(logged_configuration(), name,
-                                     T::GetFullyQualifiedName(), "", node,
-                                     true) != nullptr;
+    return HasChannel(name, T::GetFullyQualifiedName(), node);
+  }
+  bool HasChannel(std::string_view name, std::string_view type,
+                  const Node *node) {
+    return configuration::GetChannel(logged_configuration(), name, type, "",
+                                     node, true) != nullptr;
   }
 
   template <typename T>
@@ -235,6 +262,14 @@
       RemapLoggedChannel<T>(name, node);
     }
   }
+  template <typename T>
+  void MaybeRenameLoggedChannel(std::string_view name, const Node *node,
+                                std::string_view new_name,
+                                const std::vector<MapT> &add_maps = {}) {
+    if (HasChannel<T>(name, node)) {
+      RenameLoggedChannel<T>(name, node, new_name, add_maps);
+    }
+  }
 
   // Returns true if the channel exists on the node and was logged.
   template <typename T>
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index fcbd77b..7214a36 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -96,9 +96,6 @@
   // passing in a separate config.
   LogReader reader(logfile, &config_.message());
 
-  // Confirm that we can remap logged channels to point to new buses.
-  reader.RemapLoggedChannel<aos::examples::Ping>("/test", "/original");
-
   // This sends out the fetched messages and advances time to the start of the
   // log file.
   reader.Register();
@@ -111,8 +108,8 @@
   int ping_count = 10;
   int pong_count = 10;
 
-  // Confirm that the ping value matches in the remapped channel location.
-  test_event_loop->MakeWatcher("/original/test",
+  // Confirm that the ping value matches.
+  test_event_loop->MakeWatcher("/test",
                                [&ping_count](const examples::Ping &ping) {
                                  EXPECT_EQ(ping.value(), ping_count + 1);
                                  ++ping_count;
@@ -128,6 +125,7 @@
 
   reader.event_loop_factory()->RunFor(std::chrono::seconds(100));
   EXPECT_EQ(ping_count, 2010);
+  EXPECT_EQ(pong_count, ping_count);
 }
 
 // Tests calling StartLogging twice.
diff --git a/aos/events/logging/multinode_logger_test.cc b/aos/events/logging/multinode_logger_test.cc
index f1784bf..18337be 100644
--- a/aos/events/logging/multinode_logger_test.cc
+++ b/aos/events/logging/multinode_logger_test.cc
@@ -166,10 +166,12 @@
                 UnorderedElementsAre(
                     std::make_tuple("/pi1/aos",
                                     "aos.message_bridge.ServerStatistics", 1),
-                    std::make_tuple("/test", "aos.examples.Ping", 1)))
+                    std::make_tuple("/test", "aos.examples.Ping", 1),
+                    std::make_tuple("/pi1/aos", "aos.examples.Ping", 1)))
         << " : " << logfiles_[2];
     {
       std::vector<std::tuple<std::string, std::string, int>> channel_counts = {
+          std::make_tuple("/pi1/aos", "aos.examples.Ping", 10),
           std::make_tuple("/pi1/aos", "aos.message_bridge.Timestamp", 1),
           std::make_tuple("/pi1/aos", "aos.message_bridge.ClientStatistics",
                           1)};
@@ -185,12 +187,13 @@
     }
     {
       std::vector<std::tuple<std::string, std::string, int>> channel_counts = {
+          std::make_tuple("/pi1/aos", "aos.examples.Ping", 1990),
           std::make_tuple("/pi1/aos", "aos.message_bridge.Timestamp", 199),
           std::make_tuple("/pi1/aos", "aos.message_bridge.ServerStatistics",
                           20),
           std::make_tuple("/pi1/aos", "aos.message_bridge.ClientStatistics",
                           199),
-          std::make_tuple("/pi1/aos", "aos.timing.Report", 40),
+          std::make_tuple("/pi1/aos", "aos.timing.Report", 60),
           std::make_tuple("/test", "aos.examples.Ping", 2000)};
       if (!std::get<0>(GetParam()).shared) {
         channel_counts.push_back(
@@ -237,8 +240,10 @@
 
     // Timing reports and pongs.
     EXPECT_THAT(CountChannelsData(config, logfiles_[7]),
-                UnorderedElementsAre(std::make_tuple(
-                    "/pi2/aos", "aos.message_bridge.ServerStatistics", 1)))
+                UnorderedElementsAre(
+                    std::make_tuple("/pi2/aos", "aos.examples.Ping", 1),
+                    std::make_tuple("/pi2/aos",
+                                    "aos.message_bridge.ServerStatistics", 1)))
         << " : " << logfiles_[7];
     EXPECT_THAT(
         CountChannelsData(config, logfiles_[8]),
@@ -247,12 +252,13 @@
     EXPECT_THAT(
         CountChannelsData(config, logfiles_[9]),
         UnorderedElementsAre(
+            std::make_tuple("/pi2/aos", "aos.examples.Ping", 2000),
             std::make_tuple("/pi2/aos", "aos.message_bridge.Timestamp", 200),
             std::make_tuple("/pi2/aos", "aos.message_bridge.ServerStatistics",
                             20),
             std::make_tuple("/pi2/aos", "aos.message_bridge.ClientStatistics",
                             200),
-            std::make_tuple("/pi2/aos", "aos.timing.Report", 40),
+            std::make_tuple("/pi2/aos", "aos.timing.Report", 60),
             std::make_tuple("/test", "aos.examples.Pong", 2000)))
         << " : " << logfiles_[9];
     // And ping timestamps.
@@ -946,7 +952,7 @@
   VerifyParts(sorted_parts);
 }
 
-// Tests that if we remap a remapped channel, it shows up correctly.
+// Tests that if we remap a logged channel, it shows up correctly.
 TEST_P(MultinodeLoggerTest, RemapLoggedChannel) {
   time_converter_.StartEqual();
   {
@@ -1025,6 +1031,117 @@
   reader.Deregister();
 }
 
+// Tests that if we rename a logged channel, it shows up correctly.
+TEST_P(MultinodeLoggerTest, RenameLoggedChannel) {
+  std::vector<std::string> actual_filenames;
+  time_converter_.StartEqual();
+  {
+    LoggerState pi1_logger = MakeLogger(pi1_);
+    LoggerState pi2_logger = MakeLogger(pi2_);
+
+    event_loop_factory_.RunFor(chrono::milliseconds(95));
+
+    StartLogger(&pi1_logger);
+    StartLogger(&pi2_logger);
+
+    event_loop_factory_.RunFor(chrono::milliseconds(20000));
+
+    pi1_logger.AppendAllFilenames(&actual_filenames);
+    pi2_logger.AppendAllFilenames(&actual_filenames);
+  }
+
+  LogReader reader(SortParts(actual_filenames));
+
+  // Rename just on pi2. Add some global maps just to verify they get added in
+  // the config and used correctly.
+  std::vector<MapT> maps;
+  {
+    MapT map;
+    map.match = std::make_unique<ChannelT>();
+    map.match->name = "/foo*";
+    map.match->source_node = "pi1";
+    map.rename = std::make_unique<ChannelT>();
+    map.rename->name = "/pi1/foo";
+    maps.emplace_back(std::move(map));
+  }
+  {
+    MapT map;
+    map.match = std::make_unique<ChannelT>();
+    map.match->name = "/foo*";
+    map.match->source_node = "pi2";
+    map.rename = std::make_unique<ChannelT>();
+    map.rename->name = "/pi2/foo";
+    maps.emplace_back(std::move(map));
+  }
+  {
+    MapT map;
+    map.match = std::make_unique<ChannelT>();
+    map.match->name = "/foo";
+    map.match->type = "aos.examples.Ping";
+    map.rename = std::make_unique<ChannelT>();
+    map.rename->name = "/foo/renamed";
+    maps.emplace_back(std::move(map));
+  }
+  reader.RenameLoggedChannel<aos::examples::Ping>(
+      "/aos", configuration::GetNode(reader.configuration(), "pi2"),
+      "/pi2/foo/renamed", maps);
+
+  SimulatedEventLoopFactory log_reader_factory(reader.configuration());
+  log_reader_factory.set_send_delay(chrono::microseconds(0));
+
+  std::vector<const Channel *> remapped_channels = reader.RemappedChannels();
+  // Note: An extra channel gets remapped automatically due to a timestamp
+  // channel being LOCAL_LOGGER'd.
+  const bool shared = std::get<0>(GetParam()).shared;
+  ASSERT_EQ(remapped_channels.size(), shared ? 1u : 2u);
+  EXPECT_EQ(remapped_channels[shared ? 0 : 1]->name()->string_view(),
+            "/pi2/foo/renamed");
+  EXPECT_EQ(remapped_channels[shared ? 0 : 1]->type()->string_view(),
+            "aos.examples.Ping");
+  if (!shared) {
+    EXPECT_EQ(remapped_channels[0]->name()->string_view(),
+              "/original/pi1/aos/remote_timestamps/pi2/pi1/aos/"
+              "aos-message_bridge-Timestamp");
+    EXPECT_EQ(remapped_channels[0]->type()->string_view(),
+              "aos.message_bridge.RemoteMessage");
+  }
+
+  reader.Register(&log_reader_factory);
+
+  const Node *pi1 =
+      configuration::GetNode(log_reader_factory.configuration(), "pi1");
+  const Node *pi2 =
+      configuration::GetNode(log_reader_factory.configuration(), "pi2");
+
+  // Confirm we can read the data on the renamed channel, just for pi2. Nothing
+  // else should have moved.
+  std::unique_ptr<EventLoop> pi2_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi2);
+  pi2_event_loop->SkipTimingReport();
+  std::unique_ptr<EventLoop> full_pi2_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi2);
+  full_pi2_event_loop->SkipTimingReport();
+  std::unique_ptr<EventLoop> pi1_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi1);
+  pi1_event_loop->SkipTimingReport();
+
+  MessageCounter<aos::examples::Ping> pi2_ping(pi2_event_loop.get(), "/aos");
+  MessageCounter<aos::examples::Ping> pi2_renamed_ping(pi2_event_loop.get(),
+                                                       "/foo");
+  MessageCounter<aos::examples::Ping> full_pi2_renamed_ping(
+      full_pi2_event_loop.get(), "/pi2/foo/renamed");
+  MessageCounter<aos::examples::Ping> pi1_ping(pi1_event_loop.get(), "/aos");
+
+  log_reader_factory.Run();
+
+  EXPECT_EQ(pi2_ping.count(), 0u);
+  EXPECT_NE(pi2_renamed_ping.count(), 0u);
+  EXPECT_NE(full_pi2_renamed_ping.count(), 0u);
+  EXPECT_NE(pi1_ping.count(), 0u);
+
+  reader.Deregister();
+}
+
 // Tests that we can remap a forwarded channel as well.
 TEST_P(MultinodeLoggerTest, RemapForwardedLoggedChannel) {
   time_converter_.StartEqual();
@@ -1102,6 +1219,109 @@
   reader.Deregister();
 }
 
+// Tests that we can rename a forwarded channel as well.
+TEST_P(MultinodeLoggerTest, RenameForwardedLoggedChannel) {
+  std::vector<std::string> actual_filenames;
+  time_converter_.StartEqual();
+  {
+    LoggerState pi1_logger = MakeLogger(pi1_);
+    LoggerState pi2_logger = MakeLogger(pi2_);
+
+    event_loop_factory_.RunFor(chrono::milliseconds(95));
+
+    StartLogger(&pi1_logger);
+    StartLogger(&pi2_logger);
+
+    event_loop_factory_.RunFor(chrono::milliseconds(20000));
+
+    pi1_logger.AppendAllFilenames(&actual_filenames);
+    pi2_logger.AppendAllFilenames(&actual_filenames);
+  }
+
+  LogReader reader(SortParts(actual_filenames));
+
+  std::vector<MapT> maps;
+  {
+    MapT map;
+    map.match = std::make_unique<ChannelT>();
+    map.match->name = "/production*";
+    map.match->source_node = "pi1";
+    map.rename = std::make_unique<ChannelT>();
+    map.rename->name = "/pi1/production";
+    maps.emplace_back(std::move(map));
+  }
+  {
+    MapT map;
+    map.match = std::make_unique<ChannelT>();
+    map.match->name = "/production*";
+    map.match->source_node = "pi2";
+    map.rename = std::make_unique<ChannelT>();
+    map.rename->name = "/pi2/production";
+    maps.emplace_back(std::move(map));
+  }
+  reader.RenameLoggedChannel<aos::examples::Ping>(
+      "/test", configuration::GetNode(reader.configuration(), "pi1"),
+      "/pi1/production", maps);
+
+  SimulatedEventLoopFactory log_reader_factory(reader.configuration());
+  log_reader_factory.set_send_delay(chrono::microseconds(0));
+
+  reader.Register(&log_reader_factory);
+
+  const Node *pi1 =
+      configuration::GetNode(log_reader_factory.configuration(), "pi1");
+  const Node *pi2 =
+      configuration::GetNode(log_reader_factory.configuration(), "pi2");
+
+  // Confirm we can read the data on the renamed channel, on both the source
+  // node and the remote node. In case of split timestamp channels, confirm that
+  // we receive the timestamp messages on the renamed channel as well.
+  std::unique_ptr<EventLoop> pi1_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi1);
+  pi1_event_loop->SkipTimingReport();
+  std::unique_ptr<EventLoop> full_pi1_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi1);
+  full_pi1_event_loop->SkipTimingReport();
+  std::unique_ptr<EventLoop> pi2_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi2);
+  pi2_event_loop->SkipTimingReport();
+
+  MessageCounter<examples::Ping> pi1_ping(pi1_event_loop.get(), "/test");
+  MessageCounter<examples::Ping> pi2_ping(pi2_event_loop.get(), "/test");
+  MessageCounter<examples::Ping> pi1_renamed_ping(pi1_event_loop.get(),
+                                                  "/pi1/production");
+  MessageCounter<examples::Ping> pi2_renamed_ping(pi2_event_loop.get(),
+                                                  "/pi1/production");
+
+  std::unique_ptr<MessageCounter<message_bridge::RemoteMessage>>
+      pi1_renamed_ping_timestamp;
+  std::unique_ptr<MessageCounter<message_bridge::RemoteMessage>>
+      pi1_ping_timestamp;
+  if (!shared()) {
+    pi1_renamed_ping_timestamp =
+        std::make_unique<MessageCounter<message_bridge::RemoteMessage>>(
+            pi1_event_loop.get(),
+            "/pi1/aos/remote_timestamps/pi2/pi1/production/aos-examples-Ping");
+    pi1_ping_timestamp =
+        std::make_unique<MessageCounter<message_bridge::RemoteMessage>>(
+            pi1_event_loop.get(),
+            "/pi1/aos/remote_timestamps/pi2/test/aos-examples-Ping");
+  }
+
+  log_reader_factory.Run();
+
+  EXPECT_EQ(pi1_ping.count(), 0u);
+  EXPECT_EQ(pi2_ping.count(), 0u);
+  EXPECT_NE(pi1_renamed_ping.count(), 0u);
+  EXPECT_NE(pi2_renamed_ping.count(), 0u);
+  if (!shared()) {
+    EXPECT_NE(pi1_renamed_ping_timestamp->count(), 0u);
+    EXPECT_EQ(pi1_ping_timestamp->count(), 0u);
+  }
+
+  reader.Deregister();
+}
+
 // Tests that we observe all the same events in log replay (for a given node)
 // whether we just register an event loop for that node or if we register a full
 // event loop factory.
diff --git a/aos/events/logging/multinode_logger_test_lib.cc b/aos/events/logging/multinode_logger_test_lib.cc
index 3ffb091..22822e7 100644
--- a/aos/events/logging/multinode_logger_test_lib.cc
+++ b/aos/events/logging/multinode_logger_test_lib.cc
@@ -115,8 +115,14 @@
   LOG(INFO) << "Logging data to " << logfiles_[0] << ", " << logfiles_[1]
             << " and " << logfiles_[2];
 
-  pi1_->OnStartup([this]() { pi1_->AlwaysStart<Ping>("ping"); });
-  pi2_->OnStartup([this]() { pi2_->AlwaysStart<Pong>("pong"); });
+  pi1_->OnStartup([this]() {
+    pi1_->AlwaysStart<Ping>("ping");
+    pi1_->AlwaysStart<Ping>("ping_local", "/aos");
+  });
+  pi2_->OnStartup([this]() {
+    pi2_->AlwaysStart<Pong>("pong");
+    pi2_->AlwaysStart<Ping>("ping_local", "/aos");
+  });
 }
 
 bool MultinodeLoggerTest::shared() const {
diff --git a/aos/events/logging/multinode_logger_test_lib.h b/aos/events/logging/multinode_logger_test_lib.h
index f3f322e..40b5933 100644
--- a/aos/events/logging/multinode_logger_test_lib.h
+++ b/aos/events/logging/multinode_logger_test_lib.h
@@ -56,13 +56,13 @@
 };
 
 constexpr std::string_view kCombinedConfigSha1() {
-  return "5d73fe35bacaa59d24f8f0c1a806fe10b783b0fcc80809ee30a9db824e82538b";
+  return "c8cd3762e42a4e19b2155f63ccec97d1627a2fbd34d3da3ea6541128ca22b899";
 }
 constexpr std::string_view kSplitConfigSha1() {
-  return "f25e8f6f90d61f41c41517e652300566228b077e44cd86f1af2af4a9bed31ad4";
+  return "0ee6360b3e82a46f3f8b241661934abac53957d494a81ed1938899c220334954";
 }
 constexpr std::string_view kReloggedSplitConfigSha1() {
-  return "f1fabd629bdf8735c3d81bc791d7a454e8e636951c26cba6426545cbc97f911f";
+  return "cc31e1a644dd7bf65d72247aea3e09b3474753e01921f3b6272f8233f288a16b";
 }
 
 LoggerState MakeLoggerState(NodeEventLoopFactory *node,
diff --git a/aos/events/logging/multinode_pingpong_combined.json b/aos/events/logging/multinode_pingpong_combined.json
index 6686360..4864674 100644
--- a/aos/events/logging/multinode_pingpong_combined.json
+++ b/aos/events/logging/multinode_pingpong_combined.json
@@ -112,6 +112,18 @@
       "num_senders": 2,
       "source_node": "pi2"
     },
+    {
+      "name": "/pi1/aos",
+      "type": "aos.examples.Ping",
+      "source_node": "pi1",
+      "frequency": 150
+    },
+    {
+      "name": "/pi2/aos",
+      "type": "aos.examples.Ping",
+      "source_node": "pi2",
+      "frequency": 150
+    },
     /* Forwarded to pi2 */
     {
       "name": "/test",
diff --git a/aos/events/logging/multinode_pingpong_split.json b/aos/events/logging/multinode_pingpong_split.json
index f5bd9cb..4cd6248 100644
--- a/aos/events/logging/multinode_pingpong_split.json
+++ b/aos/events/logging/multinode_pingpong_split.json
@@ -35,6 +35,18 @@
     },
     {
       "name": "/pi1/aos",
+      "type": "aos.examples.Ping",
+      "source_node": "pi1",
+      "frequency": 150
+    },
+    {
+      "name": "/pi2/aos",
+      "type": "aos.examples.Ping",
+      "source_node": "pi2",
+      "frequency": 150
+    },
+    {
+      "name": "/pi1/aos",
       "type": "aos.message_bridge.ServerStatistics",
       "logger": "LOCAL_LOGGER",
       "source_node": "pi1"
diff --git a/aos/events/ping_lib.cc b/aos/events/ping_lib.cc
index f9958ff..e80fd75 100644
--- a/aos/events/ping_lib.cc
+++ b/aos/events/ping_lib.cc
@@ -12,14 +12,16 @@
 
 namespace chrono = std::chrono;
 
-Ping::Ping(EventLoop *event_loop)
+Ping::Ping(EventLoop *event_loop, std::string_view channel_name)
     : event_loop_(event_loop),
-      sender_(event_loop_->MakeSender<examples::Ping>("/test")) {
+      sender_(event_loop_->MakeSender<examples::Ping>(channel_name)) {
   timer_handle_ = event_loop_->AddTimer([this]() { SendPing(); });
   timer_handle_->set_name("ping");
 
-  event_loop_->MakeWatcher(
-      "/test", [this](const examples::Pong &pong) { HandlePong(pong); });
+  if (event_loop_->HasChannel<examples::Pong>(channel_name)) {
+    event_loop_->MakeWatcher(
+        channel_name, [this](const examples::Pong &pong) { HandlePong(pong); });
+  }
 
   event_loop_->OnRun([this]() {
     timer_handle_->Setup(event_loop_->monotonic_now(),
diff --git a/aos/events/ping_lib.h b/aos/events/ping_lib.h
index 0b83d52..fec6c45 100644
--- a/aos/events/ping_lib.h
+++ b/aos/events/ping_lib.h
@@ -2,6 +2,7 @@
 #define AOS_EVENTS_PING_LIB_H_
 
 #include <chrono>
+#include <string_view>
 
 #include "aos/events/event_loop.h"
 #include "aos/events/ping_generated.h"
@@ -12,7 +13,7 @@
 // Class which sends out a Ping message every X ms, and times the response.
 class Ping {
  public:
-  Ping(EventLoop *event_loop);
+  Ping(EventLoop *event_loop, std::string_view channel_name = "/test");
 
   void set_quiet(bool quiet) { quiet_ = quiet; }
 
diff --git a/aos/logging/log_namer.cc b/aos/logging/log_namer.cc
index dfebe44..ed57caa 100644
--- a/aos/logging/log_namer.cc
+++ b/aos/logging/log_namer.cc
@@ -111,19 +111,19 @@
 
 }  // namespace
 
-std::string GetLogName(const char *basename) {
+std::optional<std::string> MaybeGetLogName(const char *basename) {
   if (FLAGS_logging_folder.empty()) {
     char folder[128];
     {
       char dev_name[8];
-      while (!FindDevice(dev_name, sizeof(dev_name))) {
+      if (!FindDevice(dev_name, sizeof(dev_name))) {
         LOG(INFO) << "Waiting for a device";
-        sleep(5);
+        return std::nullopt;
       }
       snprintf(folder, sizeof(folder), "/media/%s1", dev_name);
-      while (!FoundThumbDrive(folder)) {
+      if (!FoundThumbDrive(folder)) {
         LOG(INFO) << "Waiting for" << folder;
-        sleep(1);
+        return std::nullopt;
       }
       snprintf(folder, sizeof(folder), "/media/%s1/", dev_name);
     }
@@ -164,5 +164,21 @@
   return log_base_name;
 }
 
+std::string GetLogName(const char *basename) {
+  std::optional<std::string> log_base_name;
+
+  while (true) {
+    log_base_name = MaybeGetLogName(basename);
+
+    if (log_base_name.has_value()) {
+      break;
+    }
+
+    sleep(5);
+  }
+
+  return log_base_name.value();
+}
+
 }  // namespace logging
 }  // namespace aos
diff --git a/aos/logging/log_namer.h b/aos/logging/log_namer.h
index 72abf12..44e93bf 100644
--- a/aos/logging/log_namer.h
+++ b/aos/logging/log_namer.h
@@ -2,6 +2,7 @@
 #define AOS_LOGGING_LOG_NAMER_H_
 
 #include <string>
+#include <optional>
 
 namespace aos {
 namespace logging {
@@ -13,6 +14,11 @@
 // the form "/media/sda1/abc-123" and setup a symlink pointing to it at
 // "/media/sda1/abc-current".
 std::string GetLogName(const char *basename);
+
+// A nonblocking variant of GetLogName that you can poll instead of blocking for
+// the usb drive.
+std::optional<std::string> MaybeGetLogName(const char *basename);
+
 }  // namespace logging
 }  // namespace aos
 
diff --git a/debian/opencv.BUILD b/debian/opencv.BUILD
index c989e22..dfc3250 100644
--- a/debian/opencv.BUILD
+++ b/debian/opencv.BUILD
@@ -28,6 +28,8 @@
     "usr/lib/%s/libopencv_aruco.so.4.5",
     "usr/lib/%s/libopencv_imgcodecs.so.4.5",
     "usr/lib/%s/libopencv_ml.so.4.5",
+    "usr/lib/%s/libopencv_dnn.so.4.5",
+    "usr/lib/%s/libprotobuf.so.23",
     "usr/lib/%s/libopencv_calib3d.so.4.5",
     "usr/lib/%s/libtbb.so.2",
     "usr/lib/%s/libgtk-3.so.0",
diff --git a/frc971/control_loops/drivetrain/distance_spline.cc b/frc971/control_loops/drivetrain/distance_spline.cc
index a1f19cd..c200b55 100644
--- a/frc971/control_loops/drivetrain/distance_spline.cc
+++ b/frc971/control_loops/drivetrain/distance_spline.cc
@@ -48,8 +48,8 @@
       if (!ddend0.isApprox(ddstart1, 1e-6)) {
         AOS_LOG(
             ERROR,
-            "Splines %d and %d don't line up in the second derivative.  [%f, "
-            "%f] != [%f, %f]\n",
+            "Splines %d and %d don't line up in the second derivative.  [%.7f, "
+            "%.7f] != [%.7f, %.7f]\n",
             static_cast<int>(i - 1), static_cast<int>(i), ddend0(0, 0),
             ddend0(1, 0), ddstart1(0, 0), ddstart1(1, 0));
       }
diff --git a/frc971/control_loops/python/graph.py b/frc971/control_loops/python/graph.py
index 1cc6f57..16c792bc 100644
--- a/frc971/control_loops/python/graph.py
+++ b/frc971/control_loops/python/graph.py
@@ -23,8 +23,10 @@
         self.canvas = FigureCanvas(fig)  # a Gtk.DrawingArea
         self.canvas.set_vexpand(True)
         self.canvas.set_size_request(800, 250)
-        self.callback_id = self.canvas.mpl_connect('motion_notify_event',
-                                                   self.on_mouse_move)
+        self.mouse_move_callback = self.canvas.mpl_connect(
+            'motion_notify_event', self.on_mouse_move)
+        self.click_callback = self.canvas.mpl_connect('button_press_event',
+                                                      self.on_click)
         self.add(self.canvas)
 
         # The current graph data
@@ -99,6 +101,24 @@
             if self.cursor_watcher is not None:
                 self.cursor_watcher.queue_draw()
 
+    def on_click(self, event):
+        """Same as on_mouse_move but also selects multisplines"""
+
+        if self.data is None:
+            return
+        total_steps_taken = self.data.shape[1]
+        total_time = self.dt * total_steps_taken
+        if event.xdata is not None:
+            # clip the position if still on the canvas, but off the graph
+            self.cursor = np.clip(event.xdata, 0, total_time)
+
+            self.redraw_cursor()
+
+            # tell the field to update too
+            if self.cursor_watcher is not None:
+                self.cursor_watcher.queue_draw()
+                self.cursor_watcher.on_graph_clicked()
+
     def redraw_cursor(self):
         """Redraws the cursor line"""
         # TODO: This redraws the entire graph and isn't very snappy
diff --git a/frc971/control_loops/python/path_edit.py b/frc971/control_loops/python/path_edit.py
index b5e8c1b..1659e55 100755
--- a/frc971/control_loops/python/path_edit.py
+++ b/frc971/control_loops/python/path_edit.py
@@ -287,7 +287,11 @@
 
                 if i == 0:
                     self.draw_robot_at_point(cr, spline, 0)
-                self.draw_robot_at_point(cr, spline, 1)
+
+                is_last_spline = spline is multispline.getLibsplines()[-1]
+
+                if multispline == self.active_multispline or is_last_spline:
+                    self.draw_robot_at_point(cr, spline, 1)
 
     def export_json(self, file_name):
         export_folder = Path(
@@ -422,6 +426,15 @@
                     prev_multispline.getSplines()[-1])
             self.queue_draw()
 
+    def on_graph_clicked(self):
+        if self.graph.cursor is not None:
+            cursor = self.graph.find_cursor()
+            if cursor is None:
+                return
+            multispline_index, x = cursor
+
+            self.active_multispline_index = multispline_index
+
     def do_button_release_event(self, event):
         self.drag_start = None
 
@@ -489,7 +502,7 @@
 
             multispline, result = Multispline.nearest_distance(
                 self.multisplines, cur_p)
-            if result and result.fun < 0.1:
+            if self.control_point_index == None and result and result.fun < 0.1:
                 self.active_multispline_index = self.multisplines.index(
                     multispline)
 
diff --git a/frc971/input/redundant_joystick_data.cc b/frc971/input/redundant_joystick_data.cc
index 3274856..a25e6c3 100644
--- a/frc971/input/redundant_joystick_data.cc
+++ b/frc971/input/redundant_joystick_data.cc
@@ -9,7 +9,7 @@
 RedundantData::RedundantData(const Data &data) : joystick_map_(), data_(data) {
   // Start with a naive map.
   for (int i = 0; i < JoystickFeature::kJoysticks; i++) {
-    joystick_map_.at(i) = i;
+    joystick_map_.at(i) = -1;
   }
 
   for (int i = 0; i < JoystickFeature::kJoysticks; i++) {
@@ -32,6 +32,9 @@
 };
 
 int RedundantData::MapRedundantJoystick(int joystick) const {
+  if (joystick < 0 || joystick >= static_cast<int>(joystick_map_.size())) {
+    return -1;
+  }
   return joystick_map_.at(joystick);
 }
 
diff --git a/frc971/rockpi/build_rootfs.sh b/frc971/rockpi/build_rootfs.sh
index d19a260..d61fb48 100755
--- a/frc971/rockpi/build_rootfs.sh
+++ b/frc971/rockpi/build_rootfs.sh
@@ -229,6 +229,7 @@
 copyfile root.root 644 etc/udev/rules.d/99-usb-mount.rules
 copyfile root.root 644 etc/udev/rules.d/99-adis16505.rules
 copyfile root.root 644 etc/udev/rules.d/99-mali.rules
+copyfile root.root 644 etc/udev/rules.d/99-coral-perms.rules
 copyfile root.root 644 etc/chrony/chrony.conf
 
 target "apt-get update"
diff --git a/frc971/rockpi/contents/etc/udev/rules.d/99-coral-perms.rules b/frc971/rockpi/contents/etc/udev/rules.d/99-coral-perms.rules
new file mode 100644
index 0000000..1e9deaf
--- /dev/null
+++ b/frc971/rockpi/contents/etc/udev/rules.d/99-coral-perms.rules
@@ -0,0 +1 @@
+SUBSYSTEM=="usb", MODE="0666", GROUP="plugdev"
diff --git a/scouting/db/db.go b/scouting/db/db.go
index 718711c..ca1af9e 100644
--- a/scouting/db/db.go
+++ b/scouting/db/db.go
@@ -48,14 +48,14 @@
 }
 
 type Action struct {
-	TeamNumber      string `gorm:"primaryKey"`
-	MatchNumber     int32  `gorm:"primaryKey"`
-	SetNumber       int32  `gorm:"primaryKey"`
-	CompLevel       string `gorm:"primaryKey"`
-	CompletedAction []byte
+	TeamNumber  string `gorm:"primaryKey"`
+	MatchNumber int32  `gorm:"primaryKey"`
+	SetNumber   int32  `gorm:"primaryKey"`
+	CompLevel   string `gorm:"primaryKey"`
 	// This contains a serialized scouting.webserver.requests.ActionType flatbuffer.
-	TimeStamp   int32 `gorm:"primaryKey"`
-	CollectedBy string
+	CompletedAction []byte
+	Timestamp       int64 `gorm:"primaryKey"`
+	CollectedBy     string
 }
 
 type NotesData struct {
diff --git a/scouting/db/db_test.go b/scouting/db/db_test.go
index ea83fa3..b0d34d8 100644
--- a/scouting/db/db_test.go
+++ b/scouting/db/db_test.go
@@ -761,27 +761,27 @@
 	correct := []Action{
 		Action{
 			TeamNumber: "1235", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0000, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0000, CollectedBy: "",
 		},
 		Action{
 			TeamNumber: "1236", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0321, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0321, CollectedBy: "",
 		},
 		Action{
 			TeamNumber: "1237", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0222, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0222, CollectedBy: "",
 		},
 		Action{
 			TeamNumber: "1238", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0110, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0110, CollectedBy: "",
 		},
 		Action{
 			TeamNumber: "1239", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0004, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0004, CollectedBy: "",
 		},
 		Action{
 			TeamNumber: "1233", MatchNumber: 94, SetNumber: 1, CompLevel: "quals",
-			CompletedAction: []byte(""), TimeStamp: 0004, CollectedBy: "",
+			CompletedAction: []byte(""), Timestamp: 0005, CollectedBy: "",
 		},
 	}
 
diff --git a/scouting/scouting_test.cy.js b/scouting/scouting_test.cy.js
index 0237c4b..8ac1880 100644
--- a/scouting/scouting_test.cy.js
+++ b/scouting/scouting_test.cy.js
@@ -105,7 +105,7 @@
   });
 
   //TODO(FILIP): Verify last action when the last action header gets added.
-  it('should: be able to get to submit screen in data scouting.', () => {
+  it('should: be able to submit data scouting.', () => {
     switchToTab('Data Entry');
     headerShouldBe('Team Selection');
     clickButton('Next');
@@ -131,11 +131,11 @@
     clickButton('Endgame');
     cy.get('[type="checkbox"]').check();
 
-    // Should be on submit screen.
-    // TODO(FILIP): Verify that submitting works once we add it.
-
     clickButton('End Match');
     headerShouldBe('Review and Submit');
+
+    clickButton('Submit');
+    headerShouldBe('Success');
   });
 
   it('should: be able to return to correct screen with undo for pick and place.', () => {
diff --git a/scouting/webserver/requests/debug/BUILD b/scouting/webserver/requests/debug/BUILD
index f3f4a72..d9bb030 100644
--- a/scouting/webserver/requests/debug/BUILD
+++ b/scouting/webserver/requests/debug/BUILD
@@ -14,6 +14,7 @@
         "//scouting/webserver/requests/messages:request_all_notes_response_go_fbs",
         "//scouting/webserver/requests/messages:request_notes_for_team_response_go_fbs",
         "//scouting/webserver/requests/messages:request_shift_schedule_response_go_fbs",
+        "//scouting/webserver/requests/messages:submit_actions_response_go_fbs",
         "//scouting/webserver/requests/messages:submit_driver_ranking_response_go_fbs",
         "//scouting/webserver/requests/messages:submit_notes_response_go_fbs",
         "//scouting/webserver/requests/messages:submit_shift_schedule_response_go_fbs",
diff --git a/scouting/webserver/requests/debug/debug.go b/scouting/webserver/requests/debug/debug.go
index eb3a1ca..acb9dd4 100644
--- a/scouting/webserver/requests/debug/debug.go
+++ b/scouting/webserver/requests/debug/debug.go
@@ -16,6 +16,7 @@
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_notes_response"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_notes_for_team_response"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule_response"
+	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions_response"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking_response"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_notes_response"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_shift_schedule_response"
@@ -157,3 +158,9 @@
 		server+"/requests/submit/submit_driver_ranking", requestBytes,
 		submit_driver_ranking_response.GetRootAsSubmitDriverRankingResponse)
 }
+
+func SubmitActions(server string, requestBytes []byte) (*submit_actions_response.SubmitActionsResponseT, error) {
+	return sendMessage[submit_actions_response.SubmitActionsResponseT](
+		server+"/requests/submit/submit_actions", requestBytes,
+		submit_actions_response.GetRootAsSubmitActionsResponse)
+}
diff --git a/scouting/webserver/requests/messages/submit_actions.fbs b/scouting/webserver/requests/messages/submit_actions.fbs
index 8c79097..d8aa98d 100644
--- a/scouting/webserver/requests/messages/submit_actions.fbs
+++ b/scouting/webserver/requests/messages/submit_actions.fbs
@@ -62,5 +62,6 @@
     set_number:int (id: 2);
     comp_level:string (id: 3);
     actions_list:[Action] (id:4);
+    //TODO: delete this field
     collected_by:string (id: 5);
 }
diff --git a/scouting/webserver/requests/requests.go b/scouting/webserver/requests/requests.go
index 9305274..8646a30 100644
--- a/scouting/webserver/requests/requests.go
+++ b/scouting/webserver/requests/requests.go
@@ -56,6 +56,7 @@
 type SubmitDriverRanking = submit_driver_ranking.SubmitDriverRanking
 type SubmitDriverRankingResponseT = submit_driver_ranking_response.SubmitDriverRankingResponseT
 type SubmitActions = submit_actions.SubmitActions
+type Action = submit_actions.Action
 type SubmitActionsResponseT = submit_actions_response.SubmitActionsResponseT
 
 // The interface we expect the database abstraction to conform to.
@@ -74,6 +75,7 @@
 	QueryNotes(int32) ([]string, error)
 	AddNotes(db.NotesData) error
 	AddDriverRanking(db.DriverRankingData) error
+	AddAction(db.Action) error
 }
 
 // Handles unknown requests. Just returns a 404.
@@ -785,6 +787,62 @@
 	w.Write(builder.FinishedBytes())
 }
 
+type submitActionsHandler struct {
+	db Database
+}
+
+func (handler submitActionsHandler) ServeHTTP(w http.ResponseWriter, req *http.Request) {
+	// Get the username of the person submitting the data.
+	username := parseUsername(req)
+
+	requestBytes, err := io.ReadAll(req.Body)
+	if err != nil {
+		respondWithError(w, http.StatusBadRequest, fmt.Sprint("Failed to read request bytes:", err))
+		return
+	}
+
+	request, success := parseRequest(w, requestBytes, "SubmitActions", submit_actions.GetRootAsSubmitActions)
+	if !success {
+		return
+	}
+
+	log.Println("Got actions for match", request.MatchNumber(), "team", request.TeamNumber(), "from", username)
+
+	for i := 0; i < request.ActionsListLength(); i++ {
+
+		var action Action
+		request.ActionsList(&action, i)
+
+		dbAction := db.Action{
+			TeamNumber:  string(request.TeamNumber()),
+			MatchNumber: request.MatchNumber(),
+			SetNumber:   request.SetNumber(),
+			CompLevel:   string(request.CompLevel()),
+			//TODO: Serialize CompletedAction
+			CompletedAction: []byte{},
+			Timestamp:       action.Timestamp(),
+			CollectedBy:     username,
+		}
+
+		// Do some error checking.
+		if action.Timestamp() < 0 {
+			respondWithError(w, http.StatusBadRequest, fmt.Sprint(
+				"Invalid timestamp field value of ", action.Timestamp()))
+			return
+		}
+
+		err = handler.db.AddAction(dbAction)
+		if err != nil {
+			respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to add action to database: ", err))
+			return
+		}
+	}
+
+	builder := flatbuffers.NewBuilder(50 * 1024)
+	builder.Finish((&SubmitActionsResponseT{}).Pack(builder))
+	w.Write(builder.FinishedBytes())
+}
+
 func HandleRequests(db Database, scoutingServer server.ScoutingServer) {
 	scoutingServer.HandleFunc("/requests", unknown)
 	scoutingServer.Handle("/requests/request/all_matches", requestAllMatchesHandler{db})
@@ -796,4 +854,5 @@
 	scoutingServer.Handle("/requests/submit/shift_schedule", submitShiftScheduleHandler{db})
 	scoutingServer.Handle("/requests/request/shift_schedule", requestShiftScheduleHandler{db})
 	scoutingServer.Handle("/requests/submit/submit_driver_ranking", SubmitDriverRankingHandler{db})
+	scoutingServer.Handle("/requests/submit/submit_actions", submitActionsHandler{db})
 }
diff --git a/scouting/webserver/requests/requests_test.go b/scouting/webserver/requests/requests_test.go
index dab3174..ac644ea 100644
--- a/scouting/webserver/requests/requests_test.go
+++ b/scouting/webserver/requests/requests_test.go
@@ -752,6 +752,109 @@
 	}
 }
 
+func packAction(action *submit_actions.ActionT) []byte {
+	builder := flatbuffers.NewBuilder(50 * 1024)
+	builder.Finish((action).Pack(builder))
+	return (builder.FinishedBytes())
+}
+
+func TestAddingActions(t *testing.T) {
+	database := MockDatabase{}
+	scoutingServer := server.NewScoutingServer()
+	HandleRequests(&database, scoutingServer)
+	scoutingServer.Start(8080)
+	defer scoutingServer.Stop()
+
+	builder := flatbuffers.NewBuilder(1024)
+	builder.Finish((&submit_actions.SubmitActionsT{
+		TeamNumber:  "1234",
+		MatchNumber: 4,
+		SetNumber:   1,
+		CompLevel:   "qual",
+		ActionsList: []*submit_actions.ActionT{
+			{
+				ActionTaken: &submit_actions.ActionTypeT{
+					Type: submit_actions.ActionTypePickupObjectAction,
+					Value: &submit_actions.PickupObjectActionT{
+						ObjectType: submit_actions.ObjectTypekCube,
+						Auto:       true,
+					},
+				},
+				Timestamp: 2400,
+			},
+			{
+				ActionTaken: &submit_actions.ActionTypeT{
+					Type: submit_actions.ActionTypePlaceObjectAction,
+					Value: &submit_actions.PlaceObjectActionT{
+						ObjectType: submit_actions.ObjectTypekCube,
+						ScoreLevel: submit_actions.ScoreLevelkLow,
+						Auto:       false,
+					},
+				},
+				Timestamp: 1009,
+			},
+		},
+	}).Pack(builder))
+
+	_, err := debug.SubmitActions("http://localhost:8080", builder.FinishedBytes())
+	if err != nil {
+		t.Fatal("Failed to submit actions: ", err)
+	}
+
+	// Make sure that the data made it into the database.
+	// TODO: Add this back when we figure out how to add the serialized action into the database.
+
+	/* expectedActionsT := []*submit_actions.ActionT{
+		{
+			ActionTaken: &submit_actions.ActionTypeT{
+				Type:	submit_actions.ActionTypePickupObjectAction,
+				Value:	&submit_actions.PickupObjectActionT{
+					ObjectType: submit_actions.ObjectTypekCube,
+					Auto: true,
+				},
+			},
+			Timestamp:       2400,
+		},
+		{
+			ActionTaken: &submit_actions.ActionTypeT{
+				Type:	submit_actions.ActionTypePlaceObjectAction,
+				Value:	&submit_actions.PlaceObjectActionT{
+					ObjectType: submit_actions.ObjectTypekCube,
+					ScoreLevel: submit_actions.ScoreLevelkLow,
+					Auto: false,
+				},
+			},
+			Timestamp:       1009,
+		},
+	} */
+
+	expectedActions := []db.Action{
+		{
+			TeamNumber:      "1234",
+			MatchNumber:     4,
+			SetNumber:       1,
+			CompLevel:       "qual",
+			CollectedBy:     "debug_cli",
+			CompletedAction: []byte{},
+			Timestamp:       2400,
+		},
+		{
+			TeamNumber:      "1234",
+			MatchNumber:     4,
+			SetNumber:       1,
+			CompLevel:       "qual",
+			CollectedBy:     "debug_cli",
+			CompletedAction: []byte{},
+			Timestamp:       1009,
+		},
+	}
+
+	if !reflect.DeepEqual(expectedActions, database.actions) {
+		t.Fatal("Expected ", expectedActions, ", but got:", database.actions)
+	}
+
+}
+
 // A mocked database we can use for testing. Add functionality to this as
 // needed for your tests.
 
@@ -761,6 +864,7 @@
 	shiftSchedule  []db.Shift
 	driver_ranking []db.DriverRankingData
 	stats2023      []db.Stats2023
+	actions        []db.Action
 }
 
 func (database *MockDatabase) AddToMatch(match db.TeamMatch) error {
@@ -830,3 +934,12 @@
 func (database *MockDatabase) ReturnAllDriverRankings() ([]db.DriverRankingData, error) {
 	return database.driver_ranking, nil
 }
+
+func (database *MockDatabase) AddAction(action db.Action) error {
+	database.actions = append(database.actions, action)
+	return nil
+}
+
+func (database *MockDatabase) ReturnActions() ([]db.Action, error) {
+	return database.actions, nil
+}
diff --git a/scouting/www/entry/entry.component.ts b/scouting/www/entry/entry.component.ts
index 9ab5b7a..71c8de2 100644
--- a/scouting/www/entry/entry.component.ts
+++ b/scouting/www/entry/entry.component.ts
@@ -301,7 +301,7 @@
     builder.finish(SubmitActions.endSubmitActions(builder));
 
     const buffer = builder.asUint8Array();
-    const res = await fetch('/requests/submit/actions', {
+    const res = await fetch('/requests/submit/submit_actions', {
       method: 'POST',
       body: buffer,
     });
diff --git a/third_party/libedgetpu/libedgetpu.BUILD b/third_party/libedgetpu/libedgetpu.BUILD
index 0289452..181c93a 100644
--- a/third_party/libedgetpu/libedgetpu.BUILD
+++ b/third_party/libedgetpu/libedgetpu.BUILD
@@ -1,11 +1,27 @@
 cc_library(
-    visibility = ["//visibility:public"],
     name = "libedgetpu-k8",
-    srcs = ["k8/libedgetpu.so.1.0"]
+    srcs = ["k8/libedgetpu.so.1.0"],
+    hdrs = glob(["include/**/*.h"]),
+    strip_include_prefix = "include",
+    visibility = ["//visibility:public"],
 )
 
 cc_library(
-    visibility = ["//visibility:public"],
     name = "libedgetpu-arm",
-    srcs = ["arm/libedgetpu.so.1.0"]
-)
\ No newline at end of file
+    srcs = ["arm/libedgetpu.so.1.0"],
+    hdrs = glob(["include/**/*.h"]),
+    strip_include_prefix = "include",
+    visibility = ["//visibility:public"],
+)
+
+genrule(
+    name = "renamed_libedgetpu-arm",
+    srcs = [
+        "arm/libedgetpu.so.1.0",
+    ],
+    outs = [
+        "arm/libedgetpu.so.1",
+    ],
+    cmd = "cp $< $@",
+    visibility = ["//visibility:public"],
+)
diff --git a/third_party/libedgetpu/libedgetpu_build_script.sh b/third_party/libedgetpu/libedgetpu_build_script.sh
old mode 100644
new mode 100755
index 0eafccf..76e20db
--- a/third_party/libedgetpu/libedgetpu_build_script.sh
+++ b/third_party/libedgetpu/libedgetpu_build_script.sh
@@ -1,10 +1,18 @@
+#!/bin/bash
+#This script creates a compressed tarball file named libedgetpu-${GIT_VERSION}.tar.gz, 
+# which contains the header files, libraries, and binaries needed to use Edge TPU on both arm and x86 architectures.
+# This script assumes you have Docker installed.
+#
 # Clone the correct version of libedgetpu
 git clone https://github.com/google-coral/libedgetpu.git
 cd libedgetpu
+GIT_VERSION=ddfa7bde33c23afd8c2892182faa3e5b4e6ad94e
+git checkout ${GIT_VERSION}
 # Build libedgetpu.so.1.0 for both arm and x86
 DOCKER_CPUS="k8" DOCKER_IMAGE="ubuntu:18.04" DOCKER_TARGETS=libedgetpu make docker-build
 DOCKER_CPUS="aarch64" DOCKER_IMAGE="debian:stretch" DOCKER_TARGETS=libedgetpu make docker-build
-# Create the directory for the tarball and move the resulting files into it 
+# Create the directory for the tarball and move the resulting files into it
+rm -rf  libedgetpu-bazel
 mkdir libedgetpu-bazel
 mkdir libedgetpu-bazel/arm
 mkdir libedgetpu-bazel/k8
@@ -12,5 +20,7 @@
 cp out/direct/k8/libedgetpu.so.1.0 libedgetpu-bazel/k8
 
 # Copy header files to the include directory
-mkdir libedgetpu-bazel/include
-cp -r include/* libedgetpu-bazel/include/
+mkdir -p libedgetpu-bazel/include/tflite/
+rsync -zarv --include="*/" --include='*.h' --exclude='*' tflite/ libedgetpu-bazel/include/tflite/
+tar zcvf libedgetpu-${GIT_VERSION}.tar.gz libedgetpu-bazel
+
diff --git a/third_party/libtensorflowlite/libtensorflowlite.BUILD b/third_party/libtensorflowlite/libtensorflowlite.BUILD
index a6b837d..761ca76 100644
--- a/third_party/libtensorflowlite/libtensorflowlite.BUILD
+++ b/third_party/libtensorflowlite/libtensorflowlite.BUILD
@@ -1,16 +1,19 @@
 cc_library(
-    visibility = ["//visibility:public"],
     name = "tensorflow-k8",
+    srcs = ["k8/libtensorflowlite.so"],
     hdrs = glob(["include/**/*.h"]),
+    copts = ["-Wno-unused-parameter"],
     strip_include_prefix = "include",
-    srcs = ["k8/libtensorflowlite.so"]
+    visibility = ["//visibility:public"],
 )
 
 cc_library(
-    visibility = ["//visibility:public"],
     name = "tensorflow-arm",
+    srcs = ["arm/libtensorflowlite.so"],
     hdrs = glob(["include/**/*.h"]),
+    copts = ["-Wno-unused-parameter"],
     strip_include_prefix = "include",
-    srcs = ["arm/libtensorflowlite.so"]
+    visibility = ["//visibility:public"],
 )
 
+exports_files(["arm/libtensorflowlite.so"])
diff --git a/third_party/libtensorflowlite/tensorflow_build_script.sh b/third_party/libtensorflowlite/tensorflow_build_script.sh
old mode 100644
new mode 100755
index 6c44353..8bde976
--- a/third_party/libtensorflowlite/tensorflow_build_script.sh
+++ b/third_party/libtensorflowlite/tensorflow_build_script.sh
@@ -1,11 +1,18 @@
+#!/bin/bash
+# This script creates a compressed tarball file named tensorflow-${GIT_VERSION}.tar.gz, 
+# which contains the header files, libraries, and binaries needed to use Tensorflow Lite on both arm and x86 architectures.
+# This script assumes you have bazelisk and necessary permissions.
+#
 # Clone and checkout the correct version of Tensorflow
 git clone https://github.com/tensorflow/tensorflow.git tensorflow_src
 cd tensorflow_src
-git checkout v2.8.0
+GIT_VERSION=a4dfb8d1a71385bd6d122e4f27f86dcebb96712d
+git checkout $GIT_VERSION
 # Build libtensorflowlite.so for both arm and x86
-bazel build --config=elinux_aarch64 -c opt //tensorflow/lite:libtensorflowlite.so
-bazel build --config=native_arch_linux -c opt //tensorflow/lite:libtensorflowlite.so
-# Create the directory for the tarball and move the resulting files into it 
+bazelisk build --config=elinux_aarch64 -c opt //tensorflow/lite:libtensorflowlite.so
+bazelisk build --config=native_arch_linux -c opt //tensorflow/lite:libtensorflowlite.so
+# Create the directory for the tarball and move the resulting files into it
+rm -rf tensorflow-bazel
 mkdir tensorflow-bazel
 mkdir tensorflow-bazel/arm
 mkdir tensorflow-bazel/k8
@@ -13,5 +20,8 @@
 cp bazel-out/k8-opt/bin/tensorflow/lite/libtensorflowlite.so tensorflow-bazel/k8
 
 # Copy header files to the include directory
- mkdir -p tensorflow-bazel/tensorflow/core/util
- rsync -zarv --include='*/'  --include='*.h' --exclude='*' tensorflow/core/util tensorflow-bazel/tensorflow/core/util
\ No newline at end of file
+mkdir -p tensorflow-bazel/include/tensorflow/
+mkdir -p tensorflow-bazel/include/flatbuffers/
+rsync -zarv --include="*/" --include='*.h' --exclude='*' tensorflow/ tensorflow-bazel/include/tensorflow/
+rsync -zarv --include="*/" --include='*.h' --exclude='*' bazel-out/../../../external/flatbuffers/include/flatbuffers/ tensorflow-bazel/include/flatbuffers/
+tar zcvf tensorflow-${GIT_VERSION}.tar.gz tensorflow-bazel
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
index 8fd6d94..a97e0dd 100644
--- a/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -27,7 +27,7 @@
   static constexpr double kImuYaw = 0.0;
   static DrivetrainConfig<double> kDrivetrainConfig{
       ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
-      ::frc971::control_loops::drivetrain::LoopType::OPEN_LOOP,
+      ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
       ::frc971::control_loops::drivetrain::GyroType::SPARTAN_GYRO,
       ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
 
diff --git a/y2022_bot3/control_loops/python/drivetrain.py b/y2022_bot3/control_loops/python/drivetrain.py
index 638b3f3..7db0a05 100644
--- a/y2022_bot3/control_loops/python/drivetrain.py
+++ b/y2022_bot3/control_loops/python/drivetrain.py
@@ -24,7 +24,7 @@
     q_pos=0.24,
     q_vel=2.5,
     efficiency=0.80,
-    has_imu=True,
+    has_imu=False,
     force=True,
     kf_q_voltage=1.0,
     controller_poles=[0.82, 0.82])
diff --git a/y2022_bot3/joystick_reader.cc b/y2022_bot3/joystick_reader.cc
index 159123c..00a28be 100644
--- a/y2022_bot3/joystick_reader.cc
+++ b/y2022_bot3/joystick_reader.cc
@@ -42,7 +42,7 @@
       : ::frc971::input::ActionJoystickInput(
             event_loop,
             ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig(),
-            ::frc971::input::DrivetrainInputReader::InputType::kSteeringWheel, {}),
+            ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
         superstructure_goal_sender_(
             event_loop->MakeSender<superstructure::Goal>("/superstructure")),
         superstructure_status_fetcher_(
diff --git a/y2022_bot3/wpilib_interface.cc b/y2022_bot3/wpilib_interface.cc
index ae838f9..b1fb08a 100644
--- a/y2022_bot3/wpilib_interface.cc
+++ b/y2022_bot3/wpilib_interface.cc
@@ -334,72 +334,6 @@
       climber_encoder_left_, climber_encoder_right_;
 };
 
-class SuperstructureWriter
-    : public ::frc971::wpilib::LoopOutputHandler<superstructure::Output> {
- public:
-  SuperstructureWriter(aos::EventLoop *event_loop)
-      : frc971::wpilib::LoopOutputHandler<superstructure::Output>(
-            event_loop, "/superstructure") {}
-
-  void set_intake_roller_falcon(
-      ::std::unique_ptr<::ctre::phoenix::motorcontrol::can::TalonFX> t) {
-    intake_roller_falcon_ = std::move(t);
-    intake_roller_falcon_->ConfigSupplyCurrentLimit(
-        {true, Values::kIntakeRollerSupplyCurrentLimit(),
-         Values::kIntakeRollerSupplyCurrentLimit(), 0});
-    intake_roller_falcon_->ConfigStatorCurrentLimit(
-        {true, Values::kIntakeRollerStatorCurrentLimit(),
-         Values::kIntakeRollerStatorCurrentLimit(), 0});
-  }
-
-  void set_climber_falcon_left(std::unique_ptr<frc::TalonFX> t) {
-    climber_falcon_left_ = std::move(t);
-  }
-
-  void set_climber_falcon_right(std::unique_ptr<frc::TalonFX> t) {
-    climber_falcon_right_ = std::move(t);
-  }
-
-  void set_intake_falcon(std::unique_ptr<frc::TalonFX> t) {
-    intake_falcon_ = std::move(t);
-  }
-
- private:
-  void Stop() override {
-    AOS_LOG(WARNING, "Superstructure output too old.\n");
-    climber_falcon_left_->SetDisabled();
-    climber_falcon_right_->SetDisabled();
-    intake_falcon_->SetDisabled();
-    intake_roller_falcon_->Set(
-        ctre::phoenix::motorcontrol::ControlMode::Disabled, 0);
-  }
-
-  void Write(const superstructure::Output &output) override {
-    WritePwm(output.climber_voltage_left(), climber_falcon_left_.get());
-    WritePwm(output.climber_voltage_right(), climber_falcon_right_.get());
-    WritePwm(output.intake_voltage(), intake_falcon_.get());
-    WriteCan(output.roller_voltage(), intake_roller_falcon_.get());
-  }
-
-  static void WriteCan(const double voltage,
-                       ::ctre::phoenix::motorcontrol::can::TalonFX *falcon) {
-    falcon->Set(
-        ctre::phoenix::motorcontrol::ControlMode::PercentOutput,
-        std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) / 12.0);
-  }
-
-  template <typename T>
-  static void WritePwm(const double voltage, T *motor) {
-    motor->SetSpeed(std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) /
-                    12.0);
-  }
-
-  ::std::shared_ptr<::ctre::phoenix::motorcontrol::can::TalonFX>
-      intake_roller_falcon_;
-  ::std::unique_ptr<::frc::TalonFX> climber_falcon_left_, climber_falcon_right_,
-      intake_falcon_;
-};
-
 class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
  public:
   ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
@@ -429,11 +363,11 @@
     ::aos::ShmEventLoop sensor_reader_event_loop(&config.message());
     SensorReader sensor_reader(&sensor_reader_event_loop, values);
     sensor_reader.set_pwm_trigger(true);
-    sensor_reader.set_drivetrain_left_encoder(make_encoder(1));
-    sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
+    sensor_reader.set_drivetrain_left_encoder(make_encoder(0));
+    sensor_reader.set_drivetrain_right_encoder(make_encoder(1));
 
-    sensor_reader.set_heading_input(make_unique<frc::DigitalInput>(9));
-    sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(8));
+    sensor_reader.set_heading_input(make_unique<frc::DigitalInput>(8));
+    sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(9));
 
     sensor_reader.set_intake_encoder(make_encoder(2));
     sensor_reader.set_climber_encoder_right(make_encoder(3));
@@ -458,16 +392,12 @@
     ::frc971::wpilib::DrivetrainWriter drivetrain_writer(&output_event_loop);
     drivetrain_writer.set_left_controller0(
         ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(0)), false);
+    drivetrain_writer.set_left_controller1(
+        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(1)), false);
     drivetrain_writer.set_right_controller0(
-        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(1)), true);
-
-    SuperstructureWriter superstructure_writer(&output_event_loop);
-    superstructure_writer.set_climber_falcon_left(make_unique<frc::TalonFX>(2));
-    superstructure_writer.set_climber_falcon_right(
-        make_unique<frc::TalonFX>(3));
-    superstructure_writer.set_intake_falcon(make_unique<frc::TalonFX>(4));
-    superstructure_writer.set_intake_roller_falcon(
-        make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(0));
+        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(2)), true);
+    drivetrain_writer.set_right_controller1(
+        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(3)), true);
     AddLoop(&output_event_loop);
 
     // Thread 5.
diff --git a/y2023/BUILD b/y2023/BUILD
index 11600de..c3f7c33 100644
--- a/y2023/BUILD
+++ b/y2023/BUILD
@@ -70,8 +70,12 @@
         ":aos_config",
         "//frc971/rockpi:rockpi_config.json",
         "//y2023/constants:constants.json",
+        "//y2023/vision:game_pieces_detector_starter",
         "//y2023/vision:image_streamer_start",
         "//y2023/www:www_files",
+        "@game_pieces_edgetpu_model//file",
+        "@libedgetpu//:arm/libedgetpu.so.1",
+        "@libtensorflowlite//:arm/libtensorflowlite.so",
     ],
     dirs = [
         "//y2023/www:www_files",
diff --git a/y2023/autonomous/auto_splines.cc b/y2023/autonomous/auto_splines.cc
index c99e417..20593f9 100644
--- a/y2023/autonomous/auto_splines.cc
+++ b/y2023/autonomous/auto_splines.cc
@@ -142,6 +142,46 @@
       alliance);
 }
 
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::SplineCable1(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    aos::Alliance alliance) {
+  return FixSpline(
+      builder,
+      aos::CopyFlatBuffer<frc971::MultiSpline>(splinecable_1_, builder->fbb()),
+      alliance);
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::SplineCable2(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    aos::Alliance alliance) {
+  return FixSpline(
+      builder,
+      aos::CopyFlatBuffer<frc971::MultiSpline>(splinecable_2_, builder->fbb()),
+      alliance);
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::SplineCable3(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    aos::Alliance alliance) {
+  return FixSpline(
+      builder,
+      aos::CopyFlatBuffer<frc971::MultiSpline>(splinecable_3_, builder->fbb()),
+      alliance);
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::SplineCable4(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    aos::Alliance alliance) {
+  return FixSpline(
+      builder,
+      aos::CopyFlatBuffer<frc971::MultiSpline>(splinecable_4_, builder->fbb()),
+      alliance);
+}
+
 flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::StraightLine(
     aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
         *builder,
diff --git a/y2023/autonomous/auto_splines.h b/y2023/autonomous/auto_splines.h
index 27442f3..6921e64 100644
--- a/y2023/autonomous/auto_splines.h
+++ b/y2023/autonomous/auto_splines.h
@@ -4,7 +4,6 @@
 #include "aos/events/event_loop.h"
 #include "aos/flatbuffer_merge.h"
 #include "frc971/control_loops/control_loops_generated.h"
-#include "frc971/input/joystick_state_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
 #include "frc971/input/joystick_state_generated.h"
 /*
@@ -29,7 +28,15 @@
         spline_3_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
             "splines/spline.2.json")),
         spline_4_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
-            "splines/spline.3.json")) {}
+            "splines/spline.3.json")),
+        splinecable_1_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+            "splines/splinecable.0.json")),
+        splinecable_2_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+            "splines/splinecable.1.json")),
+        splinecable_3_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+            "splines/splinecable.2.json")),
+        splinecable_4_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+            "splines/splinecable.3.json")) {}
   static flatbuffers::Offset<frc971::MultiSpline> BasicSSpline(
       aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
           *builder,
@@ -59,6 +66,22 @@
       aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
           *builder,
       aos::Alliance alliance);
+  flatbuffers::Offset<frc971::MultiSpline> SplineCable1(
+      aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+          *builder,
+      aos::Alliance alliance);
+  flatbuffers::Offset<frc971::MultiSpline> SplineCable2(
+      aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+          *builder,
+      aos::Alliance alliance);
+  flatbuffers::Offset<frc971::MultiSpline> SplineCable3(
+      aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+          *builder,
+      aos::Alliance alliance);
+  flatbuffers::Offset<frc971::MultiSpline> SplineCable4(
+      aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+          *builder,
+      aos::Alliance alliance);
 
  private:
   aos::FlatbufferDetachedBuffer<frc971::MultiSpline> test_spline_;
@@ -66,6 +89,10 @@
   aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_2_;
   aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_3_;
   aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_4_;
+  aos::FlatbufferDetachedBuffer<frc971::MultiSpline> splinecable_1_;
+  aos::FlatbufferDetachedBuffer<frc971::MultiSpline> splinecable_2_;
+  aos::FlatbufferDetachedBuffer<frc971::MultiSpline> splinecable_3_;
+  aos::FlatbufferDetachedBuffer<frc971::MultiSpline> splinecable_4_;
 };
 
 }  // namespace autonomous
diff --git a/y2023/autonomous/autonomous_actor.cc b/y2023/autonomous/autonomous_actor.cc
index 26197e3..58c31d0 100644
--- a/y2023/autonomous/autonomous_actor.cc
+++ b/y2023/autonomous/autonomous_actor.cc
@@ -14,6 +14,7 @@
 
 DEFINE_bool(spline_auto, false, "Run simple test S-spline auto mode.");
 DEFINE_bool(charged_up, true, "If true run charged up autonomous mode");
+DEFINE_bool(charged_up_cable, false, "If true run cable side autonomous mode");
 
 namespace y2023 {
 namespace autonomous {
@@ -126,11 +127,28 @@
                    SplineDirection::kBackward),
         PlanSpline(std::bind(&AutonomousSplines::Spline4, &auto_splines_,
                              std::placeholders::_1, alliance_),
-                   SplineDirection::kForward),
-    };
+                   SplineDirection::kForward)};
 
     starting_position_ = charged_up_splines_.value()[0].starting_position();
     CHECK(starting_position_);
+  } else if (FLAGS_charged_up_cable) {
+    charged_up_cable_splines_ = {
+        PlanSpline(std::bind(&AutonomousSplines::SplineCable1, &auto_splines_,
+                             std::placeholders::_1, alliance_),
+                   SplineDirection::kBackward),
+        PlanSpline(std::bind(&AutonomousSplines::SplineCable2, &auto_splines_,
+                             std::placeholders::_1, alliance_),
+                   SplineDirection::kForward),
+        PlanSpline(std::bind(&AutonomousSplines::SplineCable3, &auto_splines_,
+                             std::placeholders::_1, alliance_),
+                   SplineDirection::kBackward),
+        PlanSpline(std::bind(&AutonomousSplines::SplineCable4, &auto_splines_,
+                             std::placeholders::_1, alliance_),
+                   SplineDirection::kForward)};
+
+    starting_position_ =
+        charged_up_cable_splines_.value()[0].starting_position();
+    CHECK(starting_position_);
   }
 
   is_planned_ = true;
@@ -188,6 +206,8 @@
     SplineAuto();
   } else if (FLAGS_charged_up) {
     ChargedUp();
+  } else if (FLAGS_charged_up_cable) {
+    ChargedUpCableSide();
   } else {
     AOS_LOG(WARNING, "No auto mode selected.");
   }
@@ -222,7 +242,7 @@
   }
 }
 
-// Charged Up 3 Game Object Autonomous.
+// Charged Up 3 Game Object Autonomous (non-cable side)
 void AutonomousActor::ChargedUp() {
   aos::monotonic_clock::time_point start_time = aos::monotonic_clock::now();
 
@@ -401,6 +421,130 @@
   }
 }
 
+// Charged Up 3 Game Object Autonomous (cable side)
+void AutonomousActor::ChargedUpCableSide() {
+  aos::monotonic_clock::time_point start_time = aos::monotonic_clock::now();
+
+  CHECK(charged_up_cable_splines_);
+
+  auto &splines = *charged_up_cable_splines_;
+
+  AOS_LOG(INFO, "Going to preload");
+
+  // Tell the superstructure a cone was preloaded
+  if (!WaitForPreloaded()) return;
+  AOS_LOG(INFO, "Moving arm");
+
+  // Place first cone on mid level
+  MidConeScore();
+
+  // Wait until the arm is at the goal to spit
+  if (!WaitForArmGoal(0.10)) return;
+  Spit();
+  if (!WaitForArmGoal(0.01)) return;
+
+  std::this_thread::sleep_for(chrono::milliseconds(100));
+
+  AOS_LOG(
+      INFO, "Placed first cone %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  // Drive and intake the cube nearest to the starting zone
+  if (!splines[0].WaitForPlan()) return;
+  splines[0].Start();
+
+  // Move arm into position to pickup a cube and start cube intake
+  PickupCube();
+
+  std::this_thread::sleep_for(chrono::milliseconds(500));
+
+  IntakeCube();
+
+  AOS_LOG(
+      INFO, "Turning on rollers %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  if (!splines[0].WaitForSplineDistanceRemaining(0.02)) return;
+
+  AOS_LOG(
+      INFO, "Got there %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  // Drive back to grid and place cube on high level
+  if (!splines[1].WaitForPlan()) return;
+  splines[1].Start();
+
+  std::this_thread::sleep_for(chrono::milliseconds(300));
+  HighCubeScore();
+
+  if (!splines[1].WaitForSplineDistanceRemaining(0.08)) return;
+  AOS_LOG(
+      INFO, "Back for first cube %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  if (!WaitForArmGoal(0.10)) return;
+
+  AOS_LOG(
+      INFO, "Arm in place for first cube %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  Spit();
+
+  if (!splines[1].WaitForSplineDistanceRemaining(0.08)) return;
+
+  AOS_LOG(
+      INFO, "Finished spline back %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  if (!WaitForArmGoal(0.05)) return;
+
+  AOS_LOG(
+      INFO, "Placed first cube %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  // Drive and intake the cube second nearest to the starting zone
+  if (!splines[2].WaitForPlan()) return;
+  splines[2].Start();
+
+  std::this_thread::sleep_for(chrono::milliseconds(200));
+  PickupCube();
+
+  std::this_thread::sleep_for(chrono::milliseconds(500));
+  IntakeCube();
+
+  if (!splines[2].WaitForSplineDistanceRemaining(0.05)) return;
+  AOS_LOG(
+      INFO, "Picked up second cube %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  // Drive back to grid and place object on mid level
+  if (!splines[3].WaitForPlan()) return;
+  splines[3].Start();
+
+  AOS_LOG(
+      INFO, "Driving back %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  MidCubeScore();
+
+  if (!splines[3].WaitForSplineDistanceRemaining(0.07)) return;
+  AOS_LOG(
+      INFO, "Got back from second cube at %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  if (!WaitForArmGoal(0.05)) return;
+  Spit();
+
+  if (!splines[3].WaitForSplineDistanceRemaining(0.02)) return;
+
+  AOS_LOG(
+      INFO, "Placed second cube %lf s\n",
+      aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
+  std::this_thread::sleep_for(chrono::milliseconds(200));
+  Neutral();
+}
+
 void AutonomousActor::SendSuperstructureGoal() {
   auto builder = superstructure_goal_sender_.MakeBuilder();
 
diff --git a/y2023/autonomous/autonomous_actor.h b/y2023/autonomous/autonomous_actor.h
index 46c8a78..31ae4f5 100644
--- a/y2023/autonomous/autonomous_actor.h
+++ b/y2023/autonomous/autonomous_actor.h
@@ -58,6 +58,7 @@
   void MaybeSendStartingPosition();
   void SplineAuto();
   void ChargedUp();
+  void ChargedUpCableSide();
   void Replan();
 
   aos::Sender<frc971::control_loops::drivetrain::LocalizerControl>
@@ -90,6 +91,7 @@
 
   std::optional<SplineHandle> test_spline_;
   std::optional<std::array<SplineHandle, 4>> charged_up_splines_;
+  std::optional<std::array<SplineHandle, 4>> charged_up_cable_splines_;
 
   // List of arm angles from arm::PointsList
   const ::std::vector<::Eigen::Matrix<double, 3, 1>> points_;
diff --git a/y2023/autonomous/splines/splinecable.0.json b/y2023/autonomous/splines/splinecable.0.json
new file mode 100644
index 0000000..3fdcfbe
--- /dev/null
+++ b/y2023/autonomous/splines/splinecable.0.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [-6.468141183035714, -6.142335156250001, -5.834629464285714, -2.6851712053571433, -2.2145624999999995, -1.7620541294642855], "spline_y": [-3.493364620535714, -3.493364620535714, -3.4752642857142853, -3.0951572544642856, -3.0770569196428568, -3.0770569196428568], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
diff --git a/y2023/autonomous/splines/splinecable.1.json b/y2023/autonomous/splines/splinecable.1.json
new file mode 100644
index 0000000..b9b4fdd
--- /dev/null
+++ b/y2023/autonomous/splines/splinecable.1.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [-1.7620541294642855, -2.2145624999999995, -2.6851712053571433, -5.8165291294642865, -6.124234821428573, -6.450040848214286], "spline_y": [-3.0770569196428568, -3.0770569196428568, -3.0951572544642856, -2.9141539062499993, -2.932254241071428, -2.932254241071428], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
diff --git a/y2023/autonomous/splines/splinecable.2.json b/y2023/autonomous/splines/splinecable.2.json
new file mode 100644
index 0000000..cef0375
--- /dev/null
+++ b/y2023/autonomous/splines/splinecable.2.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [-6.450040848214286, -6.124234821428573, -5.8165291294642865, -2.9023752232142854, -2.1059604910714285, -1.6353517857142856], "spline_y": [-2.932254241071428, -2.932254241071428, -2.9141539062499993, -3.2218595982142855, -2.6607492187499995, -2.244441517857142], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
diff --git a/y2023/autonomous/splines/splinecable.3.json b/y2023/autonomous/splines/splinecable.3.json
new file mode 100644
index 0000000..60821fe
--- /dev/null
+++ b/y2023/autonomous/splines/splinecable.3.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [-1.6353517857142856, -2.1059604910714285, -2.9023752232142854, -5.8165291294642865, -6.124234821428573, -6.450040848214286], "spline_y": [-2.244441517857142, -2.6607492187499995, -3.2218595982142855, -2.9141539062499993, -2.932254241071428, -2.932254241071428], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.0}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.0}, {"constraint_type": "VOLTAGE", "value": 10.0}]}
\ No newline at end of file
diff --git a/y2023/constants.cc b/y2023/constants.cc
index 2ab296f..b64ac3d 100644
--- a/y2023/constants.cc
+++ b/y2023/constants.cc
@@ -111,7 +111,7 @@
           0.0317706563397807 - 2.6357823523782 + 0.871932806570122;
 
       wrist->subsystem_params.zeroing_constants.measured_absolute_position =
-          2.29036834725319;
+          0.858579506535361;
 
       break;
 
@@ -132,7 +132,7 @@
           //3.11964893168338 / 3.148;
           (3.12725165289659 + 0.002) / 3.1485739705977704;
 
-      roll_joint->zeroing.measured_absolute_position = 1.78072413296938;
+      roll_joint->zeroing.measured_absolute_position = 1.79390317510529;
       roll_joint->potentiometer_offset =
           0.624713611895747 + 3.10458504917251 - 0.0966407797407789 +
           0.0257708772364788 - 0.0395076737853459 - 6.87914956118006 -
@@ -140,7 +140,7 @@
           0.709274294168941;
 
       wrist->subsystem_params.zeroing_constants.measured_absolute_position =
-          6.05398282057911;
+          4.68612810338484;
 
       break;
 
diff --git a/y2023/constants.h b/y2023/constants.h
index 2f16f1a..32ed317 100644
--- a/y2023/constants.h
+++ b/y2023/constants.h
@@ -170,7 +170,7 @@
   }
 
   // if true, tune down all the arm constants for testing.
-  static constexpr bool kArmGrannyMode() { return true; }
+  static constexpr bool kArmGrannyMode() { return false; }
 
   // the operating voltage.
   static constexpr double kArmOperatingVoltage() {
diff --git a/y2023/constants/7971.json b/y2023/constants/7971.json
index 5c0877d..74fd3aa 100644
--- a/y2023/constants/7971.json
+++ b/y2023/constants/7971.json
@@ -4,10 +4,10 @@
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-1_cam-23-01_ext_2023-02-19.json' %}
     },
     {
-      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-2_cam-23-02_ext_2023-04-05.json' %}
+      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-2_cam-23-02_ext_2023-04-08.json' %}
     },
     {
-      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-3_cam-23-03_ext_2023-04-05.json' %}
+      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-3_cam-23-03_ext_2023-04-08.json' %}
     },
     {
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-7971-4_cam-23-04_ext_2023-02-19.json' %}
diff --git a/y2023/constants/971.json b/y2023/constants/971.json
index 35a9a1e..b9351fd 100644
--- a/y2023/constants/971.json
+++ b/y2023/constants/971.json
@@ -7,7 +7,7 @@
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-2_cam-23-06_ext_2023-03-25.json' %}
     },
     {
-      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-03-26.json' %}
+      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-3_cam-23-04_ext_2023-04-10.json' %}
     },
     {
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-4_cam-23-08_ext_2023-02-22.json' %}
diff --git a/y2023/vision/BUILD b/y2023/vision/BUILD
index 0221aad..eda123e 100644
--- a/y2023/vision/BUILD
+++ b/y2023/vision/BUILD
@@ -224,11 +224,13 @@
     ],
     data = [
         "//y2023:aos_config",
+        "@game_pieces_edgetpu_model//file",
     ],
     target_compatible_with = ["@platforms//os:linux"],
     visibility = ["//y2023:__subpackages__"],
     deps = [
         ":game_pieces_fbs",
+        ":yolov5_lib",
         "//aos/events:event_loop",
         "//aos/events:shm_event_loop",
         "//frc971/vision:vision_fbs",
@@ -273,10 +275,12 @@
     name = "yolov5_lib",
     srcs = ["yolov5.cc"],
     hdrs = ["yolov5.h"],
+    copts = ["-Wno-unused-parameter"],
     deps = [
         "//third_party:opencv",
         "@com_github_gflags_gflags//:gflags",
         "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/types:span",
     ] + cpu_select({
         "amd64": [
             "@libtensorflowlite//:tensorflow-k8",
@@ -288,3 +292,9 @@
         ],
     }),
 )
+
+filegroup(
+    name = "game_pieces_detector_starter",
+    srcs = ["game_pieces_detector_starter.sh"],
+    visibility = ["//visibility:public"],
+)
diff --git a/y2023/vision/calib_files/calibration_pi-7971-2_cam-23-02_ext_2023-04-08.json b/y2023/vision/calib_files/calibration_pi-7971-2_cam-23-02_ext_2023-04-08.json
new file mode 100644
index 0000000..8728938
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-7971-2_cam-23-02_ext_2023-04-08.json
@@ -0,0 +1 @@
+{ "node_name": "pi2", "team_number": 7971, "intrinsics": [  888.573181, 0.0, 649.254517, 0.0, 888.493774, 370.136658, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ -0.482031, 0.00240341, 0.87615,  0.149719, -0.87612, -0.0100773, -0.481987, -0.000995038, 0.00767093, -0.999947, 0.00696306, 0.0062866, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [  -0.449155, 0.251979, -0.000308, -0.000179, -0.080278 ], "calibration_timestamp": 1358499769498335208, "camera_id": "23-02" }
diff --git a/y2023/vision/calib_files/calibration_pi-7971-3_cam-23-03_ext_2023-04-08.json b/y2023/vision/calib_files/calibration_pi-7971-3_cam-23-03_ext_2023-04-08.json
new file mode 100644
index 0000000..6eb481f
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-7971-3_cam-23-03_ext_2023-04-08.json
@@ -0,0 +1 @@
+{ "node_name": "pi3", "team_number": 7971, "intrinsics": [ 887.863831, 0.0, 625.956909, 0.0, 888.210205, 372.510437, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ 0.517483, 0.00906969, 0.855645, 0.156941, -0.855687, 0.00935422, 0.517409, 0.0833421, -0.00331132, -0.999915, 0.0126013, 0.0124048, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.449028, 0.257065, 0.000478, -0.000113, -0.086986 ], "calibration_timestamp": 1358501967378322133, "camera_id": "23-03" }
diff --git a/y2023/vision/calib_files/calibration_pi-971-3_cam-23-04_ext_2023-04-10.json b/y2023/vision/calib_files/calibration_pi-971-3_cam-23-04_ext_2023-04-10.json
new file mode 100644
index 0000000..f76623c
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-971-3_cam-23-04_ext_2023-04-10.json
@@ -0,0 +1,2 @@
+{ "node_name": "pi3", "team_number": 971, "intrinsics": [ 890.071899, 0.0, 620.69519, 0.0, 890.307434, 365.158844, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ 0.482409, -0.181339, -0.85697, -0.115455, -0.871457, -0.000440151, -0.490471, -0.175596, 0.0885639, 0.983421, -0.158241, 0.61873, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.449088, 0.25594, 0.000415, 0.000142, -0.084656 ], "calibration_timestamp": 1358501982039874176, "camera_id": "23-04" }
+
diff --git a/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-02-22.json b/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-02-22.json
deleted file mode 100644
index 8c86d20..0000000
--- a/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-02-22.json
+++ /dev/null
@@ -1 +0,0 @@
-{ "node_name": "pi3", "team_number": 971, "intrinsics": [ 892.627869, 0.0, 629.289978, 0.0, 891.73761, 373.299896, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ 0.492232, -0.163335, -0.855002, 0.020122, -0.866067, 0.006706, -0.499883, -0.174518, 0.087382, 0.986548, -0.138158, 0.645307, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.454901, 0.266778, -0.000316, -0.000469, -0.091357 ], "calibration_timestamp": 1358500316768663953, "camera_id": "23-07" }
\ No newline at end of file
diff --git a/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-03-26.json b/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-03-26.json
deleted file mode 100644
index 64d1c95..0000000
--- a/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-03-26.json
+++ /dev/null
@@ -1 +0,0 @@
-{ "node_name": "pi3", "team_number": 971, "intrinsics": [ 892.627869, 0.0, 629.289978, 0.0, 891.73761, 373.299896, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [0.514403, -0.183311, -0.837728, -0.0051253, -0.851817, 0.00353495, -0.523827, -0.214622, 0.0989849, 0.983049, -0.154329, 0.62819, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.454901, 0.266778, -0.000316, -0.000469, -0.091357 ], "calibration_timestamp": 1358500316768663953, "camera_id": "23-07" }
diff --git a/y2023/vision/game_pieces.cc b/y2023/vision/game_pieces.cc
index 0e2546f..8a0621d 100644
--- a/y2023/vision/game_pieces.cc
+++ b/y2023/vision/game_pieces.cc
@@ -5,95 +5,73 @@
 #include "aos/events/event_loop.h"
 #include "aos/events/shm_event_loop.h"
 #include "frc971/vision/vision_generated.h"
-
-// The best_x and best_y are pixel (x, y) cordinates. The 'best'
-// game piece is picked on proximity to the specified cordinates.
-// The cordinate should represent where we want to intake a game piece.
-// (0, 360) was chosen without any testing, just a cordinate that
-// seemed reasonable.
-
-DEFINE_uint32(
-    best_x, 0,
-    "The 'best' game piece is picked based on how close it is to this x value");
-
-DEFINE_uint32(
-    best_y, 360,
-    "The 'best' game piece is picked based on how close it is to this y value");
+#include "y2023/vision/yolov5.h"
 
 namespace y2023 {
 namespace vision {
+using aos::monotonic_clock;
 GamePiecesDetector::GamePiecesDetector(aos::EventLoop *event_loop)
     : game_pieces_sender_(event_loop->MakeSender<GamePieces>("/camera")) {
-  event_loop->MakeWatcher("/camera", [this](const CameraImage &camera_image) {
-    this->ProcessImage(camera_image);
-  });
+  model = MakeYOLOV5();
+  model->LoadModel("edgetpu_model.tflite");
+
+  event_loop->MakeWatcher(
+      "/camera", [this, event_loop](const CameraImage &camera_image) {
+        const monotonic_clock::time_point eof = monotonic_clock::time_point(
+            std::chrono::nanoseconds(camera_image.monotonic_timestamp_ns()));
+        const monotonic_clock::duration age = event_loop->monotonic_now() - eof;
+        if (age > std::chrono::milliseconds(100)) {
+          VLOG(1) << "Behind, skipping";
+          return;
+        }
+
+        this->ProcessImage(camera_image);
+      });
 }
 
-// TODO(FILIP): Actually do inference.
-
 void GamePiecesDetector::ProcessImage(const CameraImage &image) {
-  // Param is not used for now.
-  (void)image;
+  cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
+                          (void *)image.data()->data());
+  std::vector<Detection> detections;
+  cv::Mat image_mat(cv::Size(image.cols(), image.rows()), CV_8UC3);
+  cv::cvtColor(image_color_mat, image_mat, cv::COLOR_YUV2BGR_YUYV);
 
-  const int detection_count = 5;
+  detections = model->ProcessImage(image_mat);
 
   auto builder = game_pieces_sender_.MakeBuilder();
 
   std::vector<flatbuffers::Offset<GamePiece>> game_pieces_offsets;
 
-  float lowest_distance = std::numeric_limits<float>::max();
-  int best_distance_index = 0;
-  srand(time(0));
-
-  for (int i = 0; i < detection_count; i++) {
-    int h = rand() % 1000;
-    int w = rand() % 1000;
-    int x = rand() % 250;
-    int y = rand() % 250;
-
+  for (size_t i = 0; i < detections.size(); i++) {
     auto box_builder = builder.MakeBuilder<Box>();
-    box_builder.add_h(h);
-    box_builder.add_w(w);
-    box_builder.add_x(x);
-    box_builder.add_y(y);
+    box_builder.add_h(detections[i].box.height);
+    box_builder.add_w(detections[i].box.width);
+    box_builder.add_x(detections[i].box.x);
+    box_builder.add_y(detections[i].box.y);
     auto box_offset = box_builder.Finish();
 
     auto game_piece_builder = builder.MakeBuilder<GamePiece>();
-    game_piece_builder.add_piece_class(y2023::vision::Class::CONE_DOWN);
+    switch (detections[i].class_id) {
+      case 0:
+        game_piece_builder.add_piece_class(ConeClass::CONE);
+        break;
+      default:
+        // Should never happen.
+        game_piece_builder.add_piece_class(ConeClass::NONE);
+    }
     game_piece_builder.add_box(box_offset);
-    game_piece_builder.add_confidence(0.9);
+    game_piece_builder.add_confidence(detections[i].confidence);
     auto game_piece = game_piece_builder.Finish();
     game_pieces_offsets.push_back(game_piece);
-
-    // Center x and y values.
-    // Inference returns the top left corner of the bounding box
-    // but we want the center of the box for this.
-
-    const int center_x = x + w / 2;
-    const int center_y = y + h / 2;
-
-    // Find difference between target x, y and the x, y
-    // of the bounding box using Euclidean distance.
-
-    const int dx = FLAGS_best_x - center_x;
-    const int dy = FLAGS_best_y - center_y;
-    const float distance = std::sqrt(dx * dx + dy * dy);
-
-    if (distance < lowest_distance) {
-      lowest_distance = distance;
-      best_distance_index = i;
-    }
   };
 
-  flatbuffers::FlatBufferBuilder fbb;
-  auto game_pieces_vector = fbb.CreateVector(game_pieces_offsets);
+  auto game_pieces_vector = builder.fbb()->CreateVector(game_pieces_offsets);
 
   auto game_pieces_builder = builder.MakeBuilder<GamePieces>();
   game_pieces_builder.add_game_pieces(game_pieces_vector);
-  game_pieces_builder.add_best_piece(best_distance_index);
 
   builder.CheckOk(builder.Send(game_pieces_builder.Finish()));
 }
 
 }  // namespace vision
-}  // namespace y2023
\ No newline at end of file
+}  // namespace y2023
diff --git a/y2023/vision/game_pieces.fbs b/y2023/vision/game_pieces.fbs
index 89f7505..1792ece 100644
--- a/y2023/vision/game_pieces.fbs
+++ b/y2023/vision/game_pieces.fbs
@@ -1,6 +1,6 @@
 namespace y2023.vision;
 
-// Object class.
+// Not used by ml anymore.
 enum Class : byte {
     NONE = 0,
     CONE_UP = 1,
@@ -8,6 +8,11 @@
     CONE_DOWN = 3,
 }
 
+enum ConeClass : byte {
+    NONE = 0,
+    CONE = 1,
+}
+
 // Bounding box dimensions and position.
 // X and Y represent the top left of the bounding box.
 table Box {
@@ -18,14 +23,13 @@
 }
 
 table GamePiece {
-    piece_class:Class (id: 0);
+    piece_class:ConeClass (id: 0);
     box:Box (id:1);
     confidence:float (id:2);
 }
 
 table GamePieces {
     game_pieces:[GamePiece] (id: 0);
-    best_piece:uint (id: 1); // Index of the "best piece".
 }
 
 root_type GamePieces;
diff --git a/y2023/vision/game_pieces.h b/y2023/vision/game_pieces.h
index a41d52a..a99a99b 100644
--- a/y2023/vision/game_pieces.h
+++ b/y2023/vision/game_pieces.h
@@ -5,6 +5,8 @@
 #include "frc971/vision/vision_generated.h"
 #include "y2023/vision/game_pieces_generated.h"
 
+#include "y2023/vision/yolov5.h"
+
 namespace y2023 {
 namespace vision {
 
@@ -20,6 +22,7 @@
 
  private:
   aos::Sender<GamePieces> game_pieces_sender_;
+  std::unique_ptr<YOLOV5> model;
 };
 }  // namespace vision
 }  // namespace y2023
diff --git a/y2023/vision/game_pieces_detector_starter.sh b/y2023/vision/game_pieces_detector_starter.sh
new file mode 100755
index 0000000..36dca97
--- /dev/null
+++ b/y2023/vision/game_pieces_detector_starter.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/home/pi/bin game_pieces_detector
diff --git a/y2023/vision/image_logger.cc b/y2023/vision/image_logger.cc
index e8b6bb2..29a95db 100644
--- a/y2023/vision/image_logger.cc
+++ b/y2023/vision/image_logger.cc
@@ -20,8 +20,15 @@
 
 std::unique_ptr<aos::logger::MultiNodeFilesLogNamer> MakeLogNamer(
     aos::EventLoop *event_loop) {
+  std::optional<std::string> log_name =
+      aos::logging::MaybeGetLogName("fbs_log");
+
+  if (!log_name.has_value()) {
+    return nullptr;
+  }
+
   return std::make_unique<aos::logger::MultiNodeFilesLogNamer>(
-      absl::StrCat(aos::logging::GetLogName("fbs_log"), "/"), event_loop);
+      absl::StrCat(log_name.value(), "/"), event_loop);
 }
 
 int main(int argc, char *argv[]) {
@@ -71,9 +78,14 @@
         enabled = joystick_state.enabled();
 
         if (!logging && enabled) {
+          auto log_namer = MakeLogNamer(&event_loop);
+          if (log_namer == nullptr) {
+            return;
+          }
+
           // Start logging if we just got enabled
           LOG(INFO) << "Starting logging";
-          logger.StartLogging(MakeLogNamer(&event_loop));
+          logger.StartLogging(std::move(log_namer));
           logging = true;
           last_rotation_time = event_loop.monotonic_now();
         } else if (logging && !enabled &&
diff --git a/y2023/vision/yolov5.cc b/y2023/vision/yolov5.cc
index 7f5aa2a..473437c 100644
--- a/y2023/vision/yolov5.cc
+++ b/y2023/vision/yolov5.cc
@@ -1,12 +1,17 @@
 #include "yolov5.h"
 
+#include <tensorflow/lite/c/common.h>
 #include <tensorflow/lite/interpreter.h>
 #include <tensorflow/lite/kernels/register.h>
 #include <tensorflow/lite/model.h>
+#include <tflite/public/edgetpu.h>
 #include <tflite/public/edgetpu_c.h>
 
-#include <opencv2/core.hpp>
+#include <chrono>
+#include <opencv2/dnn.hpp>
+#include <string>
 
+#include "absl/types/span.h"
 #include "gflags/gflags.h"
 #include "glog/logging.h"
 
@@ -21,6 +26,8 @@
 
 DEFINE_int32(nthreads, 6, "Number of threads to use during inference.");
 
+DEFINE_bool(visualize_detections, false, "Display inference output");
+
 namespace y2023 {
 namespace vision {
 
@@ -36,7 +43,7 @@
  private:
   // Convert an OpenCV Mat object to a tensor input
   // that can be fed to the TensorFlow Lite model.
-  void ConvertCVMatToTensor(const cv::Mat &src, uint8_t *in);
+  void ConvertCVMatToTensor(cv::Mat src, absl::Span<uint8_t> tensor);
 
   // Resizes, converts color space, and converts
   // image data type before inference.
@@ -48,10 +55,10 @@
                                                    const int columns);
 
   // Performs non-maximum suppression to remove overlapping bounding boxes.
-  void NonMaximumSupression(const std::vector<std::vector<float>> &orig_preds,
-                            const int rows, const int columns,
-                            std::vector<Detection> *detections,
-                            std::vector<int> *indices);
+  std::vector<Detection> NonMaximumSupression(
+      const std::vector<std::vector<float>> &orig_preds, const int rows,
+      const int columns, std::vector<Detection> *detections,
+      std::vector<int> *indices);
   // Models
   std::unique_ptr<tflite::FlatBufferModel> model_;
   std::unique_ptr<tflite::Interpreter> interpreter_;
@@ -69,35 +76,48 @@
   int img_width_;
 
   // Input of the interpreter
-  uint8_t *input_8_;
+  absl::Span<uint8_t> input_8_;
 
   // Subtract this offset from class labels to get the actual label.
   static constexpr int kClassIdOffset = 5;
 };
 
-std::unique_ptr<YOLOV5> MakeYOLOV5() {
-  YOLOV5Impl *yolo = new YOLOV5Impl();
-  return std::unique_ptr<YOLOV5>(yolo);
-}
+std::unique_ptr<YOLOV5> MakeYOLOV5() { return std::make_unique<YOLOV5Impl>(); }
 
 void YOLOV5Impl::LoadModel(const std::string path) {
-  model_ = tflite::FlatBufferModel::BuildFromFile(path.c_str());
+  VLOG(1) << "Load model: Start";
+
+  tflite::ops::builtin::BuiltinOpResolver resolver;
+
+  model_ = tflite::FlatBufferModel::VerifyAndBuildFromFile(path.c_str());
   CHECK(model_);
+  CHECK(model_->initialized());
+  VLOG(1) << "Load model: Build model from file success";
+
+  CHECK_EQ(tflite::InterpreterBuilder(*model_, resolver)(&interpreter_),
+           kTfLiteOk);
+  VLOG(1) << "Load model: Interpreter builder success";
+
   size_t num_devices;
   std::unique_ptr<edgetpu_device, decltype(&edgetpu_free_devices)> devices(
       edgetpu_list_devices(&num_devices), &edgetpu_free_devices);
-  const auto &device = devices.get()[0];
+
   CHECK_EQ(num_devices, 1ul);
-  tflite::ops::builtin::BuiltinOpResolver resolver;
-  CHECK_EQ(tflite::InterpreterBuilder(*model_, resolver)(&interpreter_),
-           kTfLiteOk);
+  const auto &device = devices.get()[0];
+  VLOG(1) << "Load model: Got Devices";
 
   auto *delegate =
       edgetpu_create_delegate(device.type, device.path, nullptr, 0);
+
   interpreter_->ModifyGraphWithDelegate(delegate);
 
+  VLOG(1) << "Load model: Modify graph with delegate complete";
+
   TfLiteStatus status = interpreter_->AllocateTensors();
-  CHECK(status == kTfLiteOk);
+  CHECK_EQ(status, kTfLiteOk);
+  CHECK(interpreter_);
+
+  VLOG(1) << "Load model: Allocate tensors success";
 
   input_ = interpreter_->inputs()[0];
   TfLiteIntArray *dims = interpreter_->tensor(input_)->dims;
@@ -105,24 +125,32 @@
   in_width_ = dims->data[2];
   in_channels_ = dims->data[3];
   in_type_ = interpreter_->tensor(input_)->type;
-  input_8_ = interpreter_->typed_tensor<uint8_t>(input_);
+
+  int tensor_size = 1;
+  for (int i = 0; i < dims->size; i++) {
+    tensor_size *= dims->data[i];
+  }
+  input_8_ =
+      absl::Span(interpreter_->typed_tensor<uint8_t>(input_), tensor_size);
 
   interpreter_->SetNumThreads(FLAGS_nthreads);
+
+  VLOG(1) << "Load model: Done";
 }
 
-void YOLOV5Impl::Preprocess(cv::Mat image) {
-  cv::resize(image, image, cv::Size(in_height_, in_width_), cv::INTER_CUBIC);
-  cv::cvtColor(image, image, cv::COLOR_BGR2RGB);
-  image.convertTo(image, CV_8U);
-}
-
-void YOLOV5Impl::ConvertCVMatToTensor(const cv::Mat &src, uint8_t *in) {
+void YOLOV5Impl::ConvertCVMatToTensor(cv::Mat src, absl::Span<uint8_t> tensor) {
   CHECK(src.type() == CV_8UC3);
   int n = 0, nc = src.channels(), ne = src.elemSize();
-  for (int y = 0; y < src.rows; ++y)
-    for (int x = 0; x < src.cols; ++x)
-      for (int c = 0; c < nc; ++c)
-        in[n++] = src.data[y * src.step + x * ne + c];
+  VLOG(2) << "ConvertCVMatToTensor: Rows " << src.rows;
+  VLOG(2) << "ConvertCVMatToTensor: Cols " << src.cols;
+  for (int y = 0; y < src.rows; ++y) {
+    auto *row_ptr = src.ptr<uint8_t>(y);
+    for (int x = 0; x < src.cols; ++x) {
+      for (int c = 0; c < nc; ++c) {
+        tensor[n++] = *(row_ptr + x * ne + c);
+      }
+    }
+  }
 }
 
 std::vector<std::vector<float>> YOLOV5Impl::TensorToVector2D(
@@ -144,7 +172,7 @@
   return result_vec;
 }
 
-void YOLOV5Impl::NonMaximumSupression(
+std::vector<Detection> YOLOV5Impl::NonMaximumSupression(
     const std::vector<std::vector<float>> &orig_preds, const int rows,
     const int columns, std::vector<Detection> *detections,
     std::vector<int> *indices)
@@ -156,19 +184,24 @@
 
   for (int i = 0; i < rows; i++) {
     if (orig_preds[i][4] > FLAGS_conf_threshold) {
-      int left = (orig_preds[i][0] - orig_preds[i][2] / 2) * img_width_;
-      int top = (orig_preds[i][1] - orig_preds[i][3] / 2) * img_height_;
-      int w = orig_preds[i][2] * img_width_;
-      int h = orig_preds[i][3] * img_height_;
+      float x = orig_preds[i][0];
+      float y = orig_preds[i][1];
+      float w = orig_preds[i][2];
+      float h = orig_preds[i][3];
+      int left = static_cast<int>((x - 0.5 * w) * img_width_);
+      int top = static_cast<int>((y - 0.5 * h) * img_height_);
+      int width = static_cast<int>(w * img_width_);
+      int height = static_cast<int>(h * img_height_);
 
       for (int j = 5; j < columns; j++) {
         scores.push_back(orig_preds[i][j] * orig_preds[i][4]);
       }
 
       cv::minMaxLoc(scores, nullptr, &confidence, nullptr, &class_id);
+      scores.clear();
       if (confidence > FLAGS_conf_threshold) {
-        Detection detection{cv::Rect(left, top, w, h), confidence,
-                            class_id.x - kClassIdOffset};
+        Detection detection{cv::Rect(left, top, width, height), confidence,
+                            class_id.x};
         detections->push_back(detection);
       }
     }
@@ -184,16 +217,31 @@
 
   cv::dnn::NMSBoxes(boxes, confidences, FLAGS_conf_threshold,
                     FLAGS_nms_threshold, *indices);
+
+  std::vector<Detection> filtered_detections;
+  for (size_t i = 0; i < indices->size(); i++) {
+    filtered_detections.push_back((*detections)[(*indices)[i]]);
+  }
+
+  VLOG(1) << "NonMaximumSupression: " << detections->size() - indices->size()
+          << " detections filtered out";
+
+  return filtered_detections;
 }
 
 std::vector<Detection> YOLOV5Impl::ProcessImage(cv::Mat frame) {
+  VLOG(1) << "\n";
+
+  auto start = std::chrono::high_resolution_clock::now();
   img_height_ = frame.rows;
   img_width_ = frame.cols;
 
-  Preprocess(frame);
+  cv::resize(frame, frame, cv::Size(in_height_, in_width_), cv::INTER_CUBIC);
+  cv::cvtColor(frame, frame, cv::COLOR_BGR2RGB);
+  frame.convertTo(frame, CV_8U);
+
   ConvertCVMatToTensor(frame, input_8_);
 
-  // Inference
   TfLiteStatus status = interpreter_->Invoke();
   CHECK_EQ(status, kTfLiteOk);
 
@@ -203,16 +251,51 @@
   int num_columns = out_dims->data[2];
 
   TfLiteTensor *src_tensor = interpreter_->tensor(interpreter_->outputs()[0]);
+
   std::vector<std::vector<float>> orig_preds =
       TensorToVector2D(src_tensor, num_rows, num_columns);
 
   std::vector<int> indices;
   std::vector<Detection> detections;
 
-  NonMaximumSupression(orig_preds, num_rows, num_columns, &detections,
-                       &indices);
+  std::vector<Detection> filtered_detections;
+  filtered_detections = NonMaximumSupression(orig_preds, num_rows, num_columns,
+                                             &detections, &indices);
+  VLOG(1) << "---";
+  for (size_t i = 0; i < filtered_detections.size(); i++) {
+    VLOG(1) << "Detection #" << i << " | Class ID #"
+            << filtered_detections[i].class_id << "  @ "
+            << filtered_detections[i].confidence << " confidence";
+  }
 
-  return detections;
+  VLOG(1) << "---";
+
+  auto stop = std::chrono::high_resolution_clock::now();
+
+  VLOG(1) << "Inference time: "
+          << std::chrono::duration_cast<std::chrono::milliseconds>(stop - start)
+                 .count();
+
+  if (FLAGS_visualize_detections) {
+    cv::resize(frame, frame, cv::Size(img_width_, img_height_), 0, 0, true);
+    for (size_t i = 0; i < filtered_detections.size(); i++) {
+      VLOG(1) << "Bounding Box | X: " << filtered_detections[i].box.x
+              << " Y: " << filtered_detections[i].box.y
+              << " W: " << filtered_detections[i].box.width
+              << " H: " << filtered_detections[i].box.height;
+      cv::rectangle(frame, filtered_detections[i].box, cv::Scalar(255, 0, 0),
+                    2);
+      cv::putText(
+          frame, std::to_string(filtered_detections[i].class_id),
+          cv::Point(filtered_detections[i].box.x, filtered_detections[i].box.y),
+          cv::FONT_HERSHEY_COMPLEX, 1.0, cv::Scalar(0, 0, 255), 1, cv::LINE_AA);
+    }
+    cv::cvtColor(frame, frame, cv::COLOR_BGR2RGB);
+    cv::imshow("yolo", frame);
+    cv::waitKey(10);
+  }
+
+  return filtered_detections;
 };
 
 }  // namespace vision
diff --git a/y2023/vision/yolov5.h b/y2023/vision/yolov5.h
index ad04350..7e2a521 100644
--- a/y2023/vision/yolov5.h
+++ b/y2023/vision/yolov5.h
@@ -7,7 +7,6 @@
 #include <fstream>
 #include <iostream>
 #include <opencv2/core.hpp>
-#include <opencv2/dnn.hpp>
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/imgcodecs.hpp>
 #include <opencv2/imgproc.hpp>
@@ -24,14 +23,14 @@
 
 class YOLOV5 {
  public:
-  virtual ~YOLOV5();
+  virtual ~YOLOV5() {}
 
   // Takes a model path as string and loads a pre-trained
   // YOLOv5 model from the specified path.
-  virtual void LoadModel(const std::string path);
+  virtual void LoadModel(const std::string path) = 0;
 
   // Takes an image and returns a Detection.
-  virtual std::vector<Detection> ProcessImage(cv::Mat image);
+  virtual std::vector<Detection> ProcessImage(cv::Mat image) = 0;
 };
 
 std::unique_ptr<YOLOV5> MakeYOLOV5();
diff --git a/y2023/y2023_logger.json b/y2023/y2023_logger.json
index df3a55b..b0ece47 100644
--- a/y2023/y2023_logger.json
+++ b/y2023/y2023_logger.json
@@ -407,8 +407,7 @@
       "user": "pi",
       "args": [
         "--enable_ftrace",
-        "--send_downsized_images",
-        "--exposure=650"
+        "--send_downsized_images"
       ],
       "nodes": [
         "logger"
@@ -448,8 +447,10 @@
       ]
     },
     {
-      "name": "game_piece_detector",
-      "executable_name": "game_piece_detector",
+      "name": "game_pieces_detector_starter",
+      "executable_name": "game_pieces_detector_starter.sh",
+      "autostart": true,
+      "user": "pi",
       "nodes": [
         "logger"
       ]