Merge "Make netcomm more important"
diff --git a/aos/events/logging/BUILD b/aos/events/logging/BUILD
index 07a751c..1edc142 100644
--- a/aos/events/logging/BUILD
+++ b/aos/events/logging/BUILD
@@ -642,6 +642,19 @@
 )
 
 cc_test(
+    name = "log_reader_utils_test",
+    srcs = ["log_reader_utils_test.cc"],
+    data = [
+        ":multinode_pingpong_combined_config",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        ":log_reader_utils",
+        ":multinode_logger_test_lib",
+    ],
+)
+
+cc_test(
     name = "multinode_logger_test",
     srcs = ["multinode_logger_test.cc"],
     copts = select({
@@ -729,3 +742,21 @@
         "@com_google_absl//absl/strings",
     ],
 )
+
+cc_binary(
+    name = "log_config_extractor",
+    srcs = [
+        "log_config_extractor.cc",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos:aos_cli_utils",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "//aos/events/logging:log_reader",
+        "@com_github_gflags_gflags//:gflags",
+        "@com_github_google_glog//:glog",
+    ],
+)
diff --git a/aos/events/logging/log_config_extractor.cc b/aos/events/logging/log_config_extractor.cc
new file mode 100644
index 0000000..aa2eed0
--- /dev/null
+++ b/aos/events/logging/log_config_extractor.cc
@@ -0,0 +1,133 @@
+#include <iostream>
+#include <filesystem>
+#include <vector>
+
+#include "aos/configuration_generated.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/logfile_sorting.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "flatbuffers/flatbuffers.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+DEFINE_string(output_path, "/tmp/",
+              "Destination folder for output files. If this flag is not used, "
+              "it stores the files in /tmp/.");
+DEFINE_bool(convert_to_json, false,
+            "If true, can be used to convert bfbs to json.");
+DEFINE_bool(bfbs, false,
+            "If true, write as a binary flatbuffer inside the output_path.");
+DEFINE_bool(json, false, "If true, write as a json inside the output_path.");
+DEFINE_bool(stripped, false,
+            "If true, write as a stripped json inside the output_path.");
+DEFINE_bool(quiet, false,
+            "If true, do not print configuration to stdout. If false, print "
+            "stripped json");
+
+namespace aos {
+
+void WriteConfig(const aos::Configuration *config, std::string output_path) {
+  // In order to deduplicate the reflection schemas in the resulting config
+  // flatbuffer (and thus reduce the size of the final flatbuffer), use
+  // MergeConfiguration() rather than the more generic
+  // RecursiveCopyFlatBuffer(). RecursiveCopyFlatBuffer() is sometimes used to
+  // reduce flatbuffer memory usage, but it only does so by rearranging memory
+  // locations, not by actually deduplicating identical flatbuffers.
+  std::vector<aos::FlatbufferVector<reflection::Schema>> schemas;
+  for (const Channel *c : *config->channels()) {
+    schemas.emplace_back(RecursiveCopyFlatBuffer(c->schema()));
+  }
+  auto config_flatbuffer = configuration::MergeConfiguration(
+      RecursiveCopyFlatBuffer(config), schemas);
+
+  if (FLAGS_bfbs) {
+    WriteFlatbufferToFile(output_path + ".bfbs", config_flatbuffer);
+    LOG(INFO) << "Done writing bfbs to " << output_path << ".bfbs";
+  }
+
+  if (FLAGS_json) {
+    WriteFlatbufferToJson(output_path + ".json", config_flatbuffer);
+    LOG(INFO) << "Done writing json to " << output_path << ".json";
+  }
+
+  if (FLAGS_stripped || !FLAGS_quiet) {
+    auto *channels = config_flatbuffer.mutable_message()->mutable_channels();
+    for (size_t i = 0; i < channels->size(); i++) {
+      channels->GetMutableObject(i)->clear_schema();
+    }
+    if (FLAGS_stripped) {
+      WriteFlatbufferToJson(output_path + ".stripped.json", config_flatbuffer);
+      LOG(INFO) << "Done writing stripped json to " << output_path
+                << ".stripped.json";
+    }
+    if (!FLAGS_quiet) {
+      std::cout << FlatbufferToJson(config_flatbuffer) << std::endl;
+    }
+  }
+}
+
+int Main(int argc, char *argv[]) {
+  CHECK(argc > 1) << "Must provide an argument";
+
+  std::string output_path = FLAGS_output_path;
+  if (output_path.back() != '/') {
+    output_path += "/";
+  }
+  if (!std::filesystem::exists(output_path)) {
+    LOG(ERROR)
+        << "Output path is invalid. Make sure the path exists before running.";
+    return EXIT_FAILURE;
+  }
+  output_path += "aos_config";
+
+  std::shared_ptr<const aos::Configuration> config;
+  // Check if the user wants to use stdin (denoted by '-') which will help
+  // convert configs in json to bfbs (see example in SetUsageMessage)
+  std::string_view arg{argv[1]};
+  if (arg == "-") {
+    // Read in everything from stdin, blocks when there's no data on stdin
+    std::string stdin_data(std::istreambuf_iterator(std::cin), {});
+    aos::FlatbufferDetachedBuffer<aos::Configuration> buffer(
+        aos::JsonToFlatbuffer(stdin_data, aos::ConfigurationTypeTable()));
+    WriteConfig(&buffer.message(), output_path);
+  } else if (FLAGS_convert_to_json) {
+    aos::FlatbufferDetachedBuffer config = aos::configuration::ReadConfig(arg);
+    WriteFlatbufferToJson(output_path + ".json", config);
+    LOG(INFO) << "Done writing json to " << output_path << ".json";
+  } else {
+    const std::vector<std::string> unsorted_logfiles =
+        aos::logger::FindLogs(argc, argv);
+
+    const std::vector<aos::logger::LogFile> logfiles =
+        aos::logger::SortParts(unsorted_logfiles);
+
+    WriteConfig(logfiles[0].config.get(), output_path);
+  }
+  return EXIT_SUCCESS;
+}
+
+}  // namespace aos
+
+int main(int argc, char *argv[]) {
+  gflags::SetUsageMessage(
+      "Binary to output the configuration of a log.\n"
+      "# print config as stripped json to stdout\n"
+      "# path to log should always be absolute path.\n"
+      "log_config_extractor /path/to/log\n"
+      "# write config to ~/work/results/aos_config.bfbs and "
+      "~/work/results/aos_config.json with no stdout "
+      "output\n"
+      "# make sure the output paths are valid and absolute paths.\n"
+      "log_config_extractor /path/to/log --output_path=~/work/results/ --bfbs "
+      "--json --quiet\n"
+      "# pass json config by stdin and output as bfbs\n"
+      "cat aos_config.json | log_config_extractor - --output_path "
+      "/absolute/path/to/dir --bfbs\n"
+      "# This can also be used to convert a bfbs file of config to json\n"
+      "log_config_extractor /path/to/config.bfbs --convert_to_json");
+
+  aos::InitGoogle(&argc, &argv);
+  return aos::Main(argc, argv);
+}
diff --git a/aos/events/logging/log_reader.cc b/aos/events/logging/log_reader.cc
index fb63e79..fa5e5d5 100644
--- a/aos/events/logging/log_reader.cc
+++ b/aos/events/logging/log_reader.cc
@@ -618,7 +618,7 @@
             ? nullptr
             : std::make_unique<TimestampMapper>(std::move(filtered_parts)),
         filters_.get(), std::bind(&LogReader::NoticeRealtimeEnd, this), node,
-        State::ThreadedBuffering::kNo, MaybeMakeReplayChannelIndicies(node));
+        State::ThreadedBuffering::kNo, MaybeMakeReplayChannelIndices(node));
     State *state = states_[node_index].get();
     state->SetNodeEventLoopFactory(
         event_loop_factory_->GetNodeEventLoopFactory(node),
@@ -809,7 +809,7 @@
             ? nullptr
             : std::make_unique<TimestampMapper>(std::move(filtered_parts)),
         filters_.get(), std::bind(&LogReader::NoticeRealtimeEnd, this), node,
-        State::ThreadedBuffering::kYes, MaybeMakeReplayChannelIndicies(node));
+        State::ThreadedBuffering::kYes, MaybeMakeReplayChannelIndices(node));
     State *state = states_[node_index].get();
 
     state->SetChannelCount(logged_configuration()->channels()->size());
@@ -1333,7 +1333,8 @@
                                    RemapConflict conflict_handling) {
   if (replay_channels_ != nullptr) {
     CHECK(std::find(replay_channels_->begin(), replay_channels_->end(),
-                    std::make_pair(name, type)) != 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.";
   }
@@ -1668,13 +1669,13 @@
   // TODO(austin): Lazily re-build to save CPU?
 }
 
-std::unique_ptr<const ReplayChannelIndicies>
-LogReader::MaybeMakeReplayChannelIndicies(const Node *node) {
+std::unique_ptr<const ReplayChannelIndices>
+LogReader::MaybeMakeReplayChannelIndices(const Node *node) {
   if (replay_channels_ == nullptr) {
     return nullptr;
   } else {
-    std::unique_ptr<ReplayChannelIndicies> replay_channel_indicies =
-        std::make_unique<ReplayChannelIndicies>();
+    std::unique_ptr<ReplayChannelIndices> replay_channel_indices =
+        std::make_unique<ReplayChannelIndices>();
     for (auto const &channel : *replay_channels_) {
       const Channel *ch = configuration::GetChannel(
           logged_configuration(), channel.first, channel.second, "", node);
@@ -1686,10 +1687,10 @@
       }
       const size_t channel_index =
           configuration::ChannelIndex(logged_configuration(), ch);
-      replay_channel_indicies->emplace_back(channel_index);
+      replay_channel_indices->emplace_back(channel_index);
     }
-    std::sort(replay_channel_indicies->begin(), replay_channel_indicies->end());
-    return replay_channel_indicies;
+    std::sort(replay_channel_indices->begin(), replay_channel_indices->end());
+    return replay_channel_indices;
   }
 }
 
@@ -1748,16 +1749,19 @@
     message_bridge::MultiNodeNoncausalOffsetEstimator *multinode_filters,
     std::function<void()> notice_realtime_end, const Node *node,
     LogReader::State::ThreadedBuffering threading,
-    std::unique_ptr<const ReplayChannelIndicies> replay_channel_indicies)
+    std::unique_ptr<const ReplayChannelIndices> replay_channel_indices)
     : timestamp_mapper_(std::move(timestamp_mapper)),
       notice_realtime_end_(notice_realtime_end),
       node_(node),
       multinode_filters_(multinode_filters),
       threading_(threading),
-      replay_channel_indicies_(std::move(replay_channel_indicies)) {
-  if (replay_channel_indicies_ != nullptr) {
+      replay_channel_indices_(std::move(replay_channel_indices)) {
+  // If timestamp_mapper_ is nullptr, then there are no log parts associated
+  // with this node. If there are no log parts for the node, there will be no
+  // log data, and so we do not need to worry about the replay channel filters.
+  if (replay_channel_indices_ != nullptr && timestamp_mapper_ != nullptr) {
     timestamp_mapper_->set_replay_channels_callback(
-        [filter = replay_channel_indicies_.get()](
+        [filter = replay_channel_indices_.get()](
             const TimestampedMessage &message) -> bool {
           auto const begin = filter->cbegin();
           auto const end = filter->cend();
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index fd5a935..d4936f1 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -33,9 +33,9 @@
 
 // Vector of pair of name and type of the channel
 using ReplayChannels =
-    std::vector<std::pair<std::string_view, std::string_view>>;
+    std::vector<std::pair<std::string, std::string>>;
 // Vector of channel indices
-using ReplayChannelIndicies = std::vector<size_t>;
+using ReplayChannelIndices = std::vector<size_t>;
 
 // We end up with one of the following 3 log file types.
 //
@@ -350,7 +350,7 @@
           message_bridge::MultiNodeNoncausalOffsetEstimator *multinode_filters,
           std::function<void()> notice_realtime_end, const Node *node,
           ThreadedBuffering threading,
-          std::unique_ptr<const ReplayChannelIndicies> replay_channel_indicies);
+          std::unique_ptr<const ReplayChannelIndices> replay_channel_indices);
 
     // Connects up the timestamp mappers.
     void AddPeer(State *peer);
@@ -753,12 +753,12 @@
     // If a ReplayChannels was passed to LogReader, this will hold the
     // indices of the channels to replay for the Node represented by
     // the instance of LogReader::State.
-    std::unique_ptr<const ReplayChannelIndicies> replay_channel_indicies_;
+    std::unique_ptr<const ReplayChannelIndices> replay_channel_indices_;
   };
 
   // If a ReplayChannels was passed to LogReader then creates a
-  // ReplayChannelIndicies for the given node. Otherwise, returns a nullptr.
-  std::unique_ptr<const ReplayChannelIndicies> MaybeMakeReplayChannelIndicies(
+  // ReplayChannelIndices for the given node. Otherwise, returns a nullptr.
+  std::unique_ptr<const ReplayChannelIndices> MaybeMakeReplayChannelIndices(
       const Node *node);
 
   // Node index -> State.
diff --git a/aos/events/logging/log_reader_utils_test.cc b/aos/events/logging/log_reader_utils_test.cc
new file mode 100644
index 0000000..9977be9
--- /dev/null
+++ b/aos/events/logging/log_reader_utils_test.cc
@@ -0,0 +1,129 @@
+#include "aos/events/logging/log_reader_utils.h"
+
+#include "aos/events/logging/multinode_logger_test_lib.h"
+#include "aos/events/ping_lib.h"
+#include "aos/events/pong_lib.h"
+#include "aos/testing/tmpdir.h"
+
+namespace aos::logger::testing {
+
+namespace chrono = std::chrono;
+// Created this test fixture because the test case checks for channel names
+// which are different in different configs
+using MultinodeLoggerOneConfigTest = MultinodeLoggerTest;
+
+INSTANTIATE_TEST_SUITE_P(
+    All, MultinodeLoggerOneConfigTest,
+    ::testing::Combine(::testing::Values(ConfigParams{
+                           "multinode_pingpong_combined_config.json", true,
+                           kCombinedConfigSha1(), kCombinedConfigSha1()}),
+                       ::testing::ValuesIn(SupportedCompressionAlgorithms())));
+
+// This test is to check if we are able to get the right channels from a log
+// given nodes and applications using the function ChannelsInLog
+TEST_P(MultinodeLoggerOneConfigTest, ChannelsInLogTest) {
+  // Run the logger
+  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));
+  }
+
+  auto sorted_parts = SortParts(logfiles_);
+  // Read all the sorted log files
+  LogReader reader(sorted_parts);
+
+  std::vector<const Node *> active_nodes;
+  std::vector<std::string> applications;
+  // Get the active node
+  active_nodes.emplace_back(
+      configuration::GetNode(reader.configuration(), "pi1"));
+
+  // Get the application for which you want to check channels
+  applications.push_back("ping");
+  aos::logger::ChannelsInLogResult channels =
+      aos::logger::ChannelsInLog(sorted_parts, active_nodes, applications);
+
+  // Check for the right sender channels
+  std::vector<std::string> expected_senders;
+  expected_senders.push_back("/pi1/aos aos.logging.LogMessageFbs");
+  expected_senders.push_back("/pi1/aos aos.timing.Report");
+  expected_senders.push_back("/test aos.examples.Ping");
+
+  std::vector<std::string> check_senders;
+  for (const auto &sender : channels.senders.value()) {
+    check_senders.push_back(sender.name + " " + sender.type);
+  }
+  ASSERT_THAT(check_senders,
+              ::testing::UnorderedElementsAreArray(expected_senders));
+  ASSERT_EQ(channels.senders.value().size(), 3);
+
+  // Check for the right watcher channels
+  std::vector<std::string> expected_watchers;
+  expected_watchers.push_back("/test aos.examples.Pong");
+  std::vector<std::string> check_watchers;
+  for (const auto &watcher : channels.watchers.value()) {
+    check_watchers.push_back(watcher.name + " " + watcher.type);
+  }
+  ASSERT_THAT(check_watchers,
+              ::testing::UnorderedElementsAreArray(expected_watchers));
+  ASSERT_EQ(channels.watchers.value().size(), 1);
+
+  // There no fetcher channels, check for none
+  ASSERT_EQ(channels.fetchers.value().size(), 0);
+}
+
+// Test to run log reader with replay channels via simulated event loop
+TEST_P(MultinodeLoggerOneConfigTest, SingleNodeLogReplay) {
+  time_converter_.StartEqual();
+  std::vector<std::string> actual_filenames;
+  const std::string kLogfile1_1 =
+      aos::testing::TestTmpDir() + "/multi_logfile1/";
+  util::UnlinkRecursive(kLogfile1_1);
+
+  {
+    LoggerState pi1_logger = MakeLoggerState(
+        pi1_, &event_loop_factory_, SupportedCompressionAlgorithms()[0]);
+    pi2_->DisableStatistics();
+    pi2_->Disconnect(pi1_->node());
+    pi1_->Disconnect(pi2_->node());
+    pi1_logger.StartLogger(kLogfile1_1);
+    event_loop_factory_.RunFor(chrono::milliseconds(20000));
+    pi1_logger.AppendAllFilenames(&actual_filenames);
+  }
+
+  ReplayChannels replay_channels{{"/test", "aos.examples.Ping"}};
+  LogReader reader(logger::SortParts(actual_filenames), &config_.message(),
+                   &replay_channels);
+  SimulatedEventLoopFactory log_reader_factory(reader.configuration());
+  int ping_count = 0;
+  int pong_count = 0;
+
+  // This sends out the fetched messages and advances time to the start of the
+  // log file.
+  reader.Register(&log_reader_factory);
+
+  const Node *pi1 =
+      configuration::GetNode(log_reader_factory.configuration(), "pi1");
+
+  std::unique_ptr<EventLoop> pi1_event_loop =
+      log_reader_factory.MakeEventLoop("test", pi1);
+  pi1_event_loop->MakeWatcher(
+      "/test", [&ping_count](const examples::Ping &) { ++ping_count; });
+  pi1_event_loop->MakeWatcher(
+      "/test", [&pong_count](const examples::Pong &) { ++pong_count; });
+
+  int sent_messages = 1999;
+  reader.event_loop_factory()->Run();
+  EXPECT_EQ(ping_count, sent_messages);
+  EXPECT_EQ(pong_count, 0);
+  reader.Deregister();
+}
+}  // namespace aos::logger::testing
diff --git a/aos/events/logging/log_replayer.cc b/aos/events/logging/log_replayer.cc
index 0f7444a..c91464c 100644
--- a/aos/events/logging/log_replayer.cc
+++ b/aos/events/logging/log_replayer.cc
@@ -57,19 +57,16 @@
   const std::vector<aos::logger::LogFile> logfiles =
       aos::logger::SortParts(unsorted_logfiles);
 
+  aos::logger::LogReader config_reader(logfiles);
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
       FLAGS_config.empty()
-          ? aos::FlatbufferDetachedBuffer<aos::Configuration>::Empty()
+          ? CopyFlatBuffer<aos::Configuration>(config_reader.configuration())
           : aos::configuration::ReadConfig(FLAGS_config);
 
   if (FLAGS_plot_timing) {
-    aos::logger::LogReader config_reader(logfiles);
-
     // Go through the effort to add a ReplayTiming channel to ensure that we
     // can capture timing information from the replay.
-    const aos::Configuration *raw_config = FLAGS_config.empty()
-                                               ? config_reader.configuration()
-                                               : &config.message();
+    const aos::Configuration *raw_config = &config.message();
     aos::ChannelT channel_overrides;
     channel_overrides.max_size = 10000;
     channel_overrides.frequency = 10000;
@@ -90,8 +87,7 @@
           ? std::nullopt
           : std::make_optional(aos::JsonToFlatbuffer<ReplayConfig>(
                 aos::util::ReadFileToStringOrDie(FLAGS_replay_config.data())));
-
-  std::vector<std::pair<std::string_view, std::string_view>> message_filter;
+  std::vector<std::pair<std::string, std::string>> message_filter;
   if (FLAGS_skip_sender_channels && replay_config.has_value()) {
     CHECK(replay_config.value().message().has_active_nodes());
     std::vector<const Node *> active_nodes;
@@ -112,7 +108,7 @@
         ChannelsInLog(logfiles, active_nodes, applications);
     for (auto const &channel :
          channels.watchers_and_fetchers_without_senders.value()) {
-      message_filter.emplace_back(std::make_pair(channel.name, channel.type));
+      message_filter.emplace_back(channel.name, channel.type);
     }
   }
 
@@ -120,7 +116,8 @@
       logfiles, &config.message(),
       message_filter.empty() ? nullptr : &message_filter);
 
-  if (replay_config.has_value()) {
+  if (replay_config.has_value() &&
+      replay_config.value().message().has_remap_channels()) {
     for (auto const &remap_channel :
          *replay_config.value().message().remap_channels()) {
       auto const &channel = remap_channel->channel();
diff --git a/aos/events/logging/multinode_logger_test.cc b/aos/events/logging/multinode_logger_test.cc
index bc1f5b8..f1784bf 100644
--- a/aos/events/logging/multinode_logger_test.cc
+++ b/aos/events/logging/multinode_logger_test.cc
@@ -18,21 +18,14 @@
 using aos::testing::ArtifactPath;
 using aos::testing::MessageCounter;
 
-constexpr std::string_view kCombinedConfigSha1(
-    "5d73fe35bacaa59d24f8f0c1a806fe10b783b0fcc80809ee30a9db824e82538b");
-constexpr std::string_view kSplitConfigSha1(
-    "f25e8f6f90d61f41c41517e652300566228b077e44cd86f1af2af4a9bed31ad4");
-constexpr std::string_view kReloggedSplitConfigSha1(
-    "f1fabd629bdf8735c3d81bc791d7a454e8e636951c26cba6426545cbc97f911f");
-
 INSTANTIATE_TEST_SUITE_P(
     All, MultinodeLoggerTest,
     ::testing::Combine(
         ::testing::Values(
             ConfigParams{"multinode_pingpong_combined_config.json", true,
-                         kCombinedConfigSha1, kCombinedConfigSha1},
+                         kCombinedConfigSha1(), kCombinedConfigSha1()},
             ConfigParams{"multinode_pingpong_split_config.json", false,
-                         kSplitConfigSha1, kReloggedSplitConfigSha1}),
+                         kSplitConfigSha1(), kReloggedSplitConfigSha1()}),
         ::testing::ValuesIn(SupportedCompressionAlgorithms())));
 
 INSTANTIATE_TEST_SUITE_P(
@@ -40,9 +33,9 @@
     ::testing::Combine(
         ::testing::Values(
             ConfigParams{"multinode_pingpong_combined_config.json", true,
-                         kCombinedConfigSha1, kCombinedConfigSha1},
+                         kCombinedConfigSha1(), kCombinedConfigSha1()},
             ConfigParams{"multinode_pingpong_split_config.json", false,
-                         kSplitConfigSha1, kReloggedSplitConfigSha1}),
+                         kSplitConfigSha1(), kReloggedSplitConfigSha1()}),
         ::testing::ValuesIn(SupportedCompressionAlgorithms())));
 
 // Tests that we can write and read simple multi-node log files.
diff --git a/aos/events/logging/multinode_logger_test_lib.h b/aos/events/logging/multinode_logger_test_lib.h
index d3754e4..f3f322e 100644
--- a/aos/events/logging/multinode_logger_test_lib.h
+++ b/aos/events/logging/multinode_logger_test_lib.h
@@ -55,6 +55,16 @@
   ~LoggerState();
 };
 
+constexpr std::string_view kCombinedConfigSha1() {
+  return "5d73fe35bacaa59d24f8f0c1a806fe10b783b0fcc80809ee30a9db824e82538b";
+}
+constexpr std::string_view kSplitConfigSha1() {
+  return "f25e8f6f90d61f41c41517e652300566228b077e44cd86f1af2af4a9bed31ad4";
+}
+constexpr std::string_view kReloggedSplitConfigSha1() {
+  return "f1fabd629bdf8735c3d81bc791d7a454e8e636951c26cba6426545cbc97f911f";
+}
+
 LoggerState MakeLoggerState(NodeEventLoopFactory *node,
                             SimulatedEventLoopFactory *factory,
                             CompressionParams params,
diff --git a/aos/events/logging/realtime_replay_test.cc b/aos/events/logging/realtime_replay_test.cc
index 888b043..2a5703a 100644
--- a/aos/events/logging/realtime_replay_test.cc
+++ b/aos/events/logging/realtime_replay_test.cc
@@ -150,20 +150,24 @@
   shm_event_loop.AddTimer([]() { LOG(INFO) << "Hello, World!"; })
       ->Setup(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
 
-  auto *const end_timer = shm_event_loop.AddTimer([&shm_event_loop]() {
-    LOG(INFO) << "All done, quitting now";
-    shm_event_loop.Exit();
-  });
-
-  // TODO(EricS) reader.OnEnd() is not working as expected when
-  // using a channel filter.
-  // keep looking for 3 seconds if some message comes, just in case
+  // End timer should not be called in this case, it should automatically quit
+  // the event loop and check for number of fetches messages
+  // This is added to make sure OnEnd is called consistently
+  // When OnEnd is not called after finishing of the log, this will eventually
+  // quit due to the end timer but will report a failure
   size_t run_seconds = 3;
+  auto *const end_timer =
+      shm_event_loop.AddTimer([&shm_event_loop, run_seconds]() {
+        shm_event_loop.Exit();
+        FAIL() << "OnEnd wasn't called on log end so quitting after "
+               << run_seconds << " seconds.";
+      });
   shm_event_loop.OnRun([&shm_event_loop, end_timer, run_seconds]() {
     LOG(INFO) << "Quitting in: " << run_seconds;
     end_timer->Setup(shm_event_loop.monotonic_now() +
                      std::chrono::seconds(run_seconds));
   });
+
   shm_event_loop.Run();
   reader.Deregister();
 
diff --git a/aos/time/BUILD b/aos/time/BUILD
index c0bd99d..04ae38f 100644
--- a/aos/time/BUILD
+++ b/aos/time/BUILD
@@ -8,7 +8,10 @@
     ],
     visibility = ["//visibility:public"],
     deps = select({
-        "@platforms//os:linux": ["@com_github_google_glog//:glog"],
+        "@platforms//os:linux": [
+            "@com_github_google_glog//:glog",
+            "@com_google_absl//absl/strings",
+        ],
         "//conditions:default": ["//motors/core"],
     }),
 )
diff --git a/aos/time/time.cc b/aos/time/time.cc
index 05510e9..4f39c36 100644
--- a/aos/time/time.cc
+++ b/aos/time/time.cc
@@ -9,6 +9,7 @@
 
 #ifdef __linux__
 
+#include "absl/strings/numbers.h"
 #include "glog/logging.h"
 
 #else  // __linux__
@@ -80,6 +81,7 @@
   return stream;
 }
 
+#ifdef __linux__
 std::optional<monotonic_clock::time_point> monotonic_clock::FromString(
     const std::string_view now) {
   // This should undo the operator << above.
@@ -97,18 +99,28 @@
 
   bool negative = now[0] == '-';
 
-  std::string sec(
+  std::string_view sec(
       now.substr(negative ? 1 : 0, now.size() - (negative ? 14 : 13)));
-  std::string nsec(now.substr(now.size() - 12, 9));
+  std::string_view nsec(now.substr(now.size() - 12, 9));
 
   if (!std::all_of(sec.begin(), sec.end(), ::isdigit) ||
       !std::all_of(nsec.begin(), nsec.end(), ::isdigit)) {
     return std::nullopt;
   }
 
+  std::chrono::seconds::rep seconds_data;
+  if (!absl::SimpleAtoi(sec, &seconds_data)) {
+    return std::nullopt;
+  }
+
+  std::chrono::nanoseconds::rep nanoseconds_data;
+  if (!absl::SimpleAtoi(nsec, &nanoseconds_data)) {
+    return std::nullopt;
+  }
+
   return monotonic_clock::time_point(
-      std::chrono::seconds((negative ? -1 : 1) * atoll(sec.c_str())) +
-      std::chrono::nanoseconds((negative ? -1 : 1) * atoll(nsec.c_str())));
+      std::chrono::seconds((negative ? -1 : 1) * seconds_data) +
+      std::chrono::nanoseconds((negative ? -1 : 1) * nanoseconds_data));
 }
 
 std::optional<realtime_clock::time_point> realtime_clock::FromString(
@@ -123,7 +135,7 @@
     return std::nullopt;
   }
 
-  std::string nsec(now.substr(now.size() - 9, 9));
+  std::string_view nsec(now.substr(now.size() - 9, 9));
 
   if (!std::all_of(nsec.begin(), nsec.end(), ::isdigit)) {
     return std::nullopt;
@@ -139,10 +151,16 @@
 
   time_t seconds = mktime(&tm);
 
+  std::chrono::nanoseconds::rep nanoseconds_data;
+  if (!absl::SimpleAtoi(nsec, &nanoseconds_data)) {
+    return std::nullopt;
+  }
+
   return realtime_clock::time_point(
       std::chrono::seconds(seconds) +
-      std::chrono::nanoseconds(atoll(nsec.c_str())));
+      std::chrono::nanoseconds(nanoseconds_data));
 }
+#endif
 
 std::ostream &operator<<(std::ostream &stream,
                          const aos::realtime_clock::time_point &now) {
diff --git a/aos/time/time.h b/aos/time/time.h
index 52d763f..cd4ecda 100644
--- a/aos/time/time.h
+++ b/aos/time/time.h
@@ -26,8 +26,10 @@
 
   // Converts the time string to a time_point if it is well formatted.  This is
   // designed to reverse operator <<.
+#ifdef __linux__
   static std::optional<monotonic_clock::time_point> FromString(
       const std::string_view now);
+#endif
 
   // Returns the epoch (0).
   static constexpr monotonic_clock::time_point epoch() {
@@ -56,8 +58,10 @@
 
   // Converts the time string to a time_point if it is well formatted.  This is
   // designed to reverse operator <<.
+#ifdef __linux__
   static std::optional<realtime_clock::time_point> FromString(
       const std::string_view now);
+#endif
 
   // Returns the epoch (0).
   static constexpr realtime_clock::time_point epoch() {
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index 1ebf1ba..60528a9 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -59,6 +59,7 @@
         "//y2022/localizer:localizer_plotter",
         "//y2022/vision:vision_plotter",
         "//y2023/localizer:corrections_plotter",
+        "//y2023/localizer:localizer_plotter",
     ],
 )
 
diff --git a/frc971/analysis/plot_index.ts b/frc971/analysis/plot_index.ts
index 1b62e42..57d5041 100644
--- a/frc971/analysis/plot_index.ts
+++ b/frc971/analysis/plot_index.ts
@@ -52,6 +52,8 @@
     '../../y2022/control_loops/superstructure/climber_plotter'
 import {plotLocalizer as plot2022Localizer} from
     '../../y2022/localizer/localizer_plotter'
+import {plotLocalizer as plot2023Localizer} from
+    '../../y2023/localizer/localizer_plotter'
 import {plotVision as plot2022Vision} from
     '../../y2022/vision/vision_plotter'
 import {plotVision as plot2023Corrections} from
@@ -115,6 +117,7 @@
   ['Down Estimator', new PlotState(plotDiv, plotDownEstimator)],
   ['Robot State', new PlotState(plotDiv, plotRobotState)],
   ['2023 Vision', new PlotState(plotDiv, plot2023Corrections)],
+  ['2023 Localizer', new PlotState(plotDiv, plot2023Localizer)],
   ['2020 Finisher', new PlotState(plotDiv, plot2020Finisher)],
   ['2020 Accelerator', new PlotState(plotDiv, plot2020Accelerator)],
   ['2020 Hood', new PlotState(plotDiv, plot2020Hood)],
diff --git a/frc971/control_loops/drivetrain/localization/utils.cc b/frc971/control_loops/drivetrain/localization/utils.cc
index ff027d0..d9e239b 100644
--- a/frc971/control_loops/drivetrain/localization/utils.cc
+++ b/frc971/control_loops/drivetrain/localization/utils.cc
@@ -30,6 +30,14 @@
              : true;
 }
 
+aos::Alliance LocalizationUtils::Alliance() {
+  joystick_state_fetcher_.Fetch();
+  return (joystick_state_fetcher_.get() != nullptr)
+             ? joystick_state_fetcher_->alliance()
+             : aos::Alliance::kInvalid;
+
+}
+
 std::optional<aos::monotonic_clock::duration> LocalizationUtils::ClockOffset(
     std::string_view node) {
   std::optional<aos::monotonic_clock::duration> monotonic_offset;
diff --git a/frc971/control_loops/drivetrain/localization/utils.h b/frc971/control_loops/drivetrain/localization/utils.h
index 26242f9..cfd443a 100644
--- a/frc971/control_loops/drivetrain/localization/utils.h
+++ b/frc971/control_loops/drivetrain/localization/utils.h
@@ -29,6 +29,7 @@
   // Returns true if either there is no JoystickState message available or if
   // we are currently in autonomous mode.
   bool MaybeInAutonomous();
+  aos::Alliance Alliance();
 
   // Returns the offset between our node and the specified node (or nullopt if
   // no offset is available). The sign of this will be such that the time on
diff --git a/scouting/www/entry/entry.component.ts b/scouting/www/entry/entry.component.ts
index aef97f7..bc6049f 100644
--- a/scouting/www/entry/entry.component.ts
+++ b/scouting/www/entry/entry.component.ts
@@ -281,12 +281,18 @@
         actionOffsets.push(actionOffset);
       }
     }
+    const teamNumberFb = builder.createString(this.teamNumber.toString());
+    const compLevelFb = builder.createString(this.compLevel);
 
     const actionsVector = SubmitActions.createActionsListVector(
       builder,
       actionOffsets
     );
     SubmitActions.startSubmitActions(builder);
+    SubmitActions.addTeamNumber(builder, teamNumberFb);
+    SubmitActions.addMatchNumber(builder, this.matchNumber);
+    SubmitActions.addSetNumber(builder, this.setNumber);
+    SubmitActions.addCompLevel(builder, compLevelFb);
     SubmitActions.addActionsList(builder, actionsVector);
     builder.finish(SubmitActions.endSubmitActions(builder));
 
diff --git a/y2023/constants/971.json b/y2023/constants/971.json
index 9f783fa..35a9a1e 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-02-22.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-4_cam-23-08_ext_2023-02-22.json' %}
diff --git a/y2023/constants/common.json b/y2023/constants/common.json
index c559810..d63c518 100644
--- a/y2023/constants/common.json
+++ b/y2023/constants/common.json
@@ -1,2 +1,6 @@
   "target_map": {% include 'y2023/vision/maps/target_map.json' %},
-  "scoring_map": {% include 'y2023/constants/scoring_map.json' %}
+  "scoring_map": {% include 'y2023/constants/scoring_map.json' %},
+  "ignore_targets": {
+    "red": [4],
+    "blue": [5]
+  }
diff --git a/y2023/constants/constants.fbs b/y2023/constants/constants.fbs
index bd038b8..61c3365 100644
--- a/y2023/constants/constants.fbs
+++ b/y2023/constants/constants.fbs
@@ -29,11 +29,19 @@
   tof:TimeOfFlight (id: 0);
 }
 
+// Set of april tag targets, by april tag ID, to ignore when on a
+// given alliance.
+table IgnoreTargets {
+  red:[uint64] (id: 0);
+  blue:[uint64] (id: 1);
+}
+
 table Constants {
   cameras:[CameraConfiguration] (id: 0);
   target_map:frc971.vision.TargetMap (id: 1);
   scoring_map:localizer.ScoringMap (id: 2);
   robot:RobotConstants (id: 3);
+  ignore_targets:IgnoreTargets (id: 4);
 }
 
 root_type Constants;
diff --git a/y2023/constants/test_data/test_team.json b/y2023/constants/test_data/test_team.json
index a1e77af..0a226f0 100644
--- a/y2023/constants/test_data/test_team.json
+++ b/y2023/constants/test_data/test_team.json
@@ -28,5 +28,9 @@
         }
       ]
     }
+  },
+  "ignore_targets": {
+    "red": [4],
+    "blue": [5]
   }
 }
diff --git a/y2023/control_loops/drivetrain/drivetrain_can_position.fbs b/y2023/control_loops/drivetrain/drivetrain_can_position.fbs
index 10d7c9a..34fbf12 100644
--- a/y2023/control_loops/drivetrain/drivetrain_can_position.fbs
+++ b/y2023/control_loops/drivetrain/drivetrain_can_position.fbs
@@ -20,6 +20,9 @@
 
   // In meters traveled on the drivetrain
   position:float (id: 5);
+
+  // Nominal range is -1 to 1, but can be -2 to +2
+  duty_cycle: float (id: 6);
 }
 
 // CAN readings from the CAN sensor reader loop
diff --git a/y2023/control_loops/superstructure/end_effector.cc b/y2023/control_loops/superstructure/end_effector.cc
index 444be0d..b600bbb 100644
--- a/y2023/control_loops/superstructure/end_effector.cc
+++ b/y2023/control_loops/superstructure/end_effector.cc
@@ -109,6 +109,9 @@
       if (!beambreak_status && !preloaded_with_cone) {
         state_ = EndEffectorState::INTAKING;
       }
+      if (game_piece_ != vision::Class::CUBE) {
+        *roller_voltage = 1.3;
+      }
       break;
     case EndEffectorState::SPITTING:
       // If spit requested, spit
diff --git a/y2023/control_loops/superstructure/superstructure_position.fbs b/y2023/control_loops/superstructure/superstructure_position.fbs
index 83ca2b6..b09e077 100644
--- a/y2023/control_loops/superstructure/superstructure_position.fbs
+++ b/y2023/control_loops/superstructure/superstructure_position.fbs
@@ -38,6 +38,9 @@
 
   // Raw position
   position:float (id: 5);
+
+  // Nominal range is -1 to 1, but can be -2 to +2
+  duty_cycle:float (id: 6);
 }
 
 table Position {
diff --git a/y2023/localizer/BUILD b/y2023/localizer/BUILD
index 7795462..43c4481 100644
--- a/y2023/localizer/BUILD
+++ b/y2023/localizer/BUILD
@@ -1,6 +1,19 @@
 load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
-load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
 load("//tools/build_rules:js.bzl", "ts_project")
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
+
+ts_project(
+    name = "localizer_plotter",
+    srcs = ["localizer_plotter.ts"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/network/www:aos_plotter",
+        "//aos/network/www:colors",
+        "//aos/network/www:proxy",
+        "//frc971/wpilib:imu_plot_utils",
+    ],
+)
 
 flatbuffer_cc_library(
     name = "status_fbs",
diff --git a/y2023/localizer/corrections_plotter.ts b/y2023/localizer/corrections_plotter.ts
index a114f3f..8a27f55 100644
--- a/y2023/localizer/corrections_plotter.ts
+++ b/y2023/localizer/corrections_plotter.ts
@@ -52,19 +52,25 @@
   const localizerOutput = aosPlotter.addMessageSource(
       '/localizer', 'frc971.controls.LocalizerOutput');
 
+  const statsPlot = aosPlotter.addPlot(element);
+  statsPlot.plot.getAxisLabels().setTitle('Statistics');
+  statsPlot.plot.getAxisLabels().setXLabel(TIME);
+  statsPlot.plot.getAxisLabels().setYLabel('[bool, enum]');
+
+  statsPlot
+      .addMessageLine(localizerStatus, ['statistics[]', 'total_accepted'])
+      .setDrawLine(false)
+      .setColor(BLUE);
+  statsPlot
+      .addMessageLine(localizerStatus, ['statistics[]', 'total_candidates'])
+      .setDrawLine(false)
+      .setColor(RED);
+
   const rejectionPlot = aosPlotter.addPlot(element);
   rejectionPlot.plot.getAxisLabels().setTitle('Rejection Reasons');
   rejectionPlot.plot.getAxisLabels().setXLabel(TIME);
   rejectionPlot.plot.getAxisLabels().setYLabel('[bool, enum]');
 
-  rejectionPlot
-      .addMessageLine(localizerStatus, ['statistics[]', 'total_accepted'])
-      .setDrawLine(false)
-      .setColor(BLUE);
-  rejectionPlot
-      .addMessageLine(localizerStatus, ['statistics[]', 'total_candidates'])
-      .setDrawLine(false)
-      .setColor(RED);
   for (let ii = 0; ii < targets.length; ++ii) {
     rejectionPlot.addMessageLine(targets[ii], ['rejection_reason'])
         .setDrawLine(false)
@@ -126,6 +132,21 @@
         .setLabel('pi' + (ii + 1));
   }
 
+  const thetaPlot = aosPlotter.addPlot(element);
+  thetaPlot.plot.getAxisLabels().setTitle('Yaw');
+  thetaPlot.plot.getAxisLabels().setXLabel(TIME);
+  thetaPlot.plot.getAxisLabels().setYLabel('[m]');
+
+  for (let ii = 0; ii < targets.length; ++ii) {
+    thetaPlot.addMessageLine(targets[ii], ['implied_robot_theta'])
+        .setDrawLine(false)
+        .setColor(PI_COLORS[ii])
+        .setLabel('pi' + (ii + 1));
+  }
+  thetaPlot.addMessageLine(localizerOutput, ['theta'])
+      .setDrawLine(false)
+      .setColor(BLUE);
+
   const aprilTagPlot = aosPlotter.addPlot(element);
   aprilTagPlot.plot.getAxisLabels().setTitle('April Tag IDs');
   aprilTagPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -137,4 +158,16 @@
         .setColor(PI_COLORS[ii])
         .setLabel('pi' + (ii + 1));
   }
+
+  const imageAgePlot = aosPlotter.addPlot(element);
+  imageAgePlot.plot.getAxisLabels().setTitle('Image Age');
+  imageAgePlot.plot.getAxisLabels().setXLabel(TIME);
+  imageAgePlot.plot.getAxisLabels().setYLabel('[sec]');
+
+  for (let ii = 0; ii < targets.length; ++ii) {
+    imageAgePlot.addMessageLine(targets[ii], ['image_age_sec'])
+        .setDrawLine(false)
+        .setColor(PI_COLORS[ii])
+        .setLabel('pi' + (ii + 1));
+  }
 }
diff --git a/y2023/localizer/localizer.cc b/y2023/localizer/localizer.cc
index efffca3..c663954 100644
--- a/y2023/localizer/localizer.cc
+++ b/y2023/localizer/localizer.cc
@@ -248,6 +248,29 @@
   return builder->Finish();
 }
 
+bool Localizer::UseAprilTag(uint64_t target_id) {
+  if (target_poses_.count(target_id) == 0) {
+    return false;
+  }
+
+  const flatbuffers::Vector<uint64_t> *ignore_tags = nullptr;
+
+  switch (utils_.Alliance()) {
+    case aos::Alliance::kRed:
+      ignore_tags =
+          CHECK_NOTNULL(constants_fetcher_.constants().ignore_targets()->red());
+      break;
+    case aos::Alliance::kBlue:
+      ignore_tags = CHECK_NOTNULL(
+          constants_fetcher_.constants().ignore_targets()->blue());
+      break;
+    case aos::Alliance::kInvalid:
+      return true;
+  }
+  return std::find(ignore_tags->begin(), ignore_tags->end(), target_id) ==
+         ignore_tags->end();
+}
+
 flatbuffers::Offset<TargetEstimateDebug> Localizer::HandleTarget(
     int camera_index, const aos::monotonic_clock::time_point capture_time,
     const frc971::vision::TargetPoseFbs &target,
@@ -267,7 +290,7 @@
   const uint64_t target_id = target.id();
   builder.add_april_tag(target_id);
   VLOG(2) << aos::FlatbufferToJson(&target);
-  if (target_poses_.count(target_id) == 0) {
+  if (!UseAprilTag(target_id)) {
     VLOG(1) << "Rejecting target due to invalid ID " << target_id;
     return RejectImage(camera_index, RejectionReason::NO_SUCH_TARGET, &builder);
   }
diff --git a/y2023/localizer/localizer.h b/y2023/localizer/localizer.h
index accb0c1..4b0715b 100644
--- a/y2023/localizer/localizer.h
+++ b/y2023/localizer/localizer.h
@@ -91,6 +91,8 @@
   static flatbuffers::Offset<CumulativeStatistics> StatisticsForCamera(
       const CameraState &camera, flatbuffers::FlatBufferBuilder *fbb);
 
+  bool UseAprilTag(uint64_t target_id);
+
   aos::EventLoop *const event_loop_;
   const frc971::control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
   frc971::constants::ConstantsFetcher<Constants> constants_fetcher_;
diff --git a/y2023/localizer/localizer_plotter.ts b/y2023/localizer/localizer_plotter.ts
new file mode 100644
index 0000000..51524fb
--- /dev/null
+++ b/y2023/localizer/localizer_plotter.ts
@@ -0,0 +1,217 @@
+// Provides a plot for debugging drivetrain-related issues.
+import {AosPlotter} from '../../aos/network/www/aos_plotter';
+import {ImuMessageHandler} from '../../frc971/wpilib/imu_plot_utils';
+import * as proxy from '../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../aos/network/www/colors';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT;
+
+export function plotLocalizer(conn: Connection, element: Element): void {
+  const aosPlotter = new AosPlotter(conn);
+
+  const position = aosPlotter.addMessageSource("/drivetrain",
+      "frc971.control_loops.drivetrain.Position");
+  const status = aosPlotter.addMessageSource(
+      '/drivetrain', 'frc971.control_loops.drivetrain.Status');
+  const output = aosPlotter.addMessageSource(
+      '/drivetrain', 'frc971.control_loops.drivetrain.Output');
+  const localizer = aosPlotter.addMessageSource(
+      '/localizer', 'y2023.localizer.Status');
+  const imu = aosPlotter.addRawMessageSource(
+      '/localizer', 'frc971.IMUValuesBatch',
+      new ImuMessageHandler(conn.getSchema('frc971.IMUValuesBatch')));
+
+  // Drivetrain Status estimated relative position
+  const positionPlot = aosPlotter.addPlot(element);
+  positionPlot.plot.getAxisLabels().setTitle("Estimated Relative Position " +
+                                             "of the Drivetrain");
+  positionPlot.plot.getAxisLabels().setXLabel(TIME);
+  positionPlot.plot.getAxisLabels().setYLabel("Relative Position (m)");
+  const leftPosition =
+      positionPlot.addMessageLine(status, ["estimated_left_position"]);
+  leftPosition.setColor(RED);
+  const rightPosition =
+      positionPlot.addMessageLine(status, ["estimated_right_position"]);
+  rightPosition.setColor(GREEN);
+  positionPlot
+      .addMessageLine(localizer, ['imu', 'left_encoder'])
+      .setColor(BROWN)
+      .setPointSize(0.0);
+  positionPlot
+      .addMessageLine(localizer, ['imu', 'right_encoder'])
+      .setColor(CYAN)
+      .setPointSize(0.0);
+  positionPlot.addMessageLine(position, ['left_encoder'])
+      .setColor(BROWN)
+      .setDrawLine(false);
+  positionPlot.addMessageLine(imu, ['left_encoder'])
+      .setColor(BROWN)
+      .setDrawLine(false);
+  positionPlot.addMessageLine(position, ['right_encoder'])
+      .setColor(CYAN)
+      .setDrawLine(false);
+  positionPlot.addMessageLine(imu, ['right_encoder'])
+      .setColor(CYAN)
+      .setDrawLine(false);
+
+
+  // Drivetrain Velocities
+  const velocityPlot = aosPlotter.addPlot(element);
+  velocityPlot.plot.getAxisLabels().setTitle('Velocity Plots');
+  velocityPlot.plot.getAxisLabels().setXLabel(TIME);
+  velocityPlot.plot.getAxisLabels().setYLabel('Wheel Velocity (m/s)');
+
+  const leftVelocity =
+      velocityPlot.addMessageLine(status, ['estimated_left_velocity']);
+  leftVelocity.setColor(RED);
+  const rightVelocity =
+      velocityPlot.addMessageLine(status, ['estimated_right_velocity']);
+  rightVelocity.setColor(GREEN);
+
+  const leftSpeed = velocityPlot.addMessageLine(position, ["left_speed"]);
+  leftSpeed.setColor(BLUE);
+  const rightSpeed = velocityPlot.addMessageLine(position, ["right_speed"]);
+  rightSpeed.setColor(BROWN);
+
+  const ekfLeftVelocity = velocityPlot.addMessageLine(
+      localizer, ['state', 'left_velocity']);
+  ekfLeftVelocity.setColor(RED);
+  ekfLeftVelocity.setPointSize(0.0);
+  const ekfRightVelocity = velocityPlot.addMessageLine(
+      localizer, ['state', 'right_velocity']);
+  ekfRightVelocity.setColor(GREEN);
+  ekfRightVelocity.setPointSize(0.0);
+
+  // Lateral velocity
+  const lateralPlot = aosPlotter.addPlot(element);
+  lateralPlot.plot.getAxisLabels().setTitle('Lateral Velocity');
+  lateralPlot.plot.getAxisLabels().setXLabel(TIME);
+  lateralPlot.plot.getAxisLabels().setYLabel('Velocity (m/s)');
+
+  lateralPlot.addMessageLine(localizer, ['state', 'lateral_velocity']).setColor(CYAN);
+
+  // Drivetrain Voltage
+  const voltagePlot = aosPlotter.addPlot(element);
+  voltagePlot.plot.getAxisLabels().setTitle('Voltage Plots');
+  voltagePlot.plot.getAxisLabels().setXLabel(TIME);
+  voltagePlot.plot.getAxisLabels().setYLabel('Voltage (V)')
+
+  voltagePlot.addMessageLine(localizer, ['state', 'left_voltage_error'])
+      .setColor(RED)
+      .setDrawLine(false);
+  voltagePlot.addMessageLine(localizer, ['state', 'right_voltage_error'])
+      .setColor(GREEN)
+      .setDrawLine(false);
+  voltagePlot.addMessageLine(output, ['left_voltage'])
+      .setColor(RED)
+      .setPointSize(0);
+  voltagePlot.addMessageLine(output, ['right_voltage'])
+      .setColor(GREEN)
+      .setPointSize(0);
+
+  // Heading
+  const yawPlot = aosPlotter.addPlot(element);
+  yawPlot.plot.getAxisLabels().setTitle('Robot Yaw');
+  yawPlot.plot.getAxisLabels().setXLabel(TIME);
+  yawPlot.plot.getAxisLabels().setYLabel('Yaw (rad)');
+
+  yawPlot.addMessageLine(status, ['localizer', 'theta']).setColor(GREEN);
+
+  yawPlot.addMessageLine(localizer, ['down_estimator', 'yaw']).setColor(BLUE);
+
+  yawPlot.addMessageLine(localizer, ['state', 'theta']).setColor(RED);
+
+  // Pitch/Roll
+  const orientationPlot = aosPlotter.addPlot(element);
+  orientationPlot.plot.getAxisLabels().setTitle('Orientation');
+  orientationPlot.plot.getAxisLabels().setXLabel(TIME);
+  orientationPlot.plot.getAxisLabels().setYLabel('Angle (rad)');
+
+  orientationPlot.addMessageLine(localizer, ['down_estimator', 'lateral_pitch'])
+      .setColor(RED)
+      .setLabel('roll');
+  orientationPlot
+      .addMessageLine(localizer, ['down_estimator', 'longitudinal_pitch'])
+      .setColor(GREEN)
+      .setLabel('pitch');
+
+  const stillPlot = aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 3]);
+  stillPlot.plot.getAxisLabels().setTitle('Still Plot');
+  stillPlot.plot.getAxisLabels().setXLabel(TIME);
+  stillPlot.plot.getAxisLabels().setYLabel('bool, g\'s');
+  stillPlot.plot.setDefaultYRange([-0.1, 1.1]);
+
+  stillPlot.addMessageLine(localizer, ['down_estimator', 'gravity_magnitude'])
+      .setColor(WHITE)
+      .setDrawLine(false);
+
+  // Absolute X Position
+  const xPositionPlot = aosPlotter.addPlot(element);
+  xPositionPlot.plot.getAxisLabels().setTitle('X Position');
+  xPositionPlot.plot.getAxisLabels().setXLabel(TIME);
+  xPositionPlot.plot.getAxisLabels().setYLabel('X Position (m)');
+
+  xPositionPlot.addMessageLine(status, ['x']).setColor(RED);
+  xPositionPlot.addMessageLine(localizer, ['down_estimator', 'position_x'])
+      .setColor(BLUE);
+  xPositionPlot.addMessageLine(localizer, ['state', 'x']).setColor(CYAN);
+
+  // Absolute Y Position
+  const yPositionPlot = aosPlotter.addPlot(element);
+  yPositionPlot.plot.getAxisLabels().setTitle('Y Position');
+  yPositionPlot.plot.getAxisLabels().setXLabel(TIME);
+  yPositionPlot.plot.getAxisLabels().setYLabel('Y Position (m)');
+
+  const localizerY = yPositionPlot.addMessageLine(status, ['y']);
+  localizerY.setColor(RED);
+  yPositionPlot.addMessageLine(localizer, ['down_estimator', 'position_y'])
+      .setColor(BLUE);
+  yPositionPlot.addMessageLine(localizer, ['state', 'y']).setColor(CYAN);
+
+  // Gyro
+  const gyroPlot = aosPlotter.addPlot(element);
+  gyroPlot.plot.getAxisLabels().setTitle('Gyro Readings');
+  gyroPlot.plot.getAxisLabels().setYLabel('Angular Velocity (rad / sec)');
+  gyroPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
+
+  const gyroX = gyroPlot.addMessageLine(imu, ['gyro_x']);
+  gyroX.setColor(RED);
+  const gyroY = gyroPlot.addMessageLine(imu, ['gyro_y']);
+  gyroY.setColor(GREEN);
+  const gyroZ = gyroPlot.addMessageLine(imu, ['gyro_z']);
+  gyroZ.setColor(BLUE);
+
+
+  const timingPlot =
+      aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+  timingPlot.plot.getAxisLabels().setTitle('Fault Counting');
+  timingPlot.plot.getAxisLabels().setXLabel(TIME);
+
+  timingPlot
+      .addMessageLine(
+          localizer, ['imu', 'imu_failures', 'imu_to_pico_checksum_mismatch'])
+      .setColor(BLUE)
+      .setDrawLine(false);
+
+  timingPlot
+      .addMessageLine(
+          localizer, ['imu', 'imu_failures', 'pico_to_pi_checksum_mismatch'])
+      .setColor(RED)
+      .setDrawLine(false);
+
+  timingPlot
+      .addMessageLine(
+          localizer, ['imu', 'imu_failures', 'other_zeroing_faults'])
+      .setColor(CYAN)
+      .setDrawLine(false);
+
+  timingPlot
+      .addMessageLine(
+          localizer, ['imu', 'imu_failures', 'missed_messages'])
+      .setColor(PINK)
+      .setDrawLine(false);
+}
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
new file mode 100644
index 0000000..64d1c95
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-971-3_cam-23-07_ext_2023-03-26.json
@@ -0,0 +1 @@
+{ "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/wpilib_interface.cc b/y2023/wpilib_interface.cc
index 2f41c91..e8d76c9 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -126,7 +126,8 @@
         supply_voltage_(talon_.GetSupplyVoltage()),
         supply_current_(talon_.GetSupplyCurrent()),
         torque_current_(talon_.GetTorqueCurrent()),
-        position_(talon_.GetPosition()) {
+        position_(talon_.GetPosition()),
+        duty_cycle_(talon_.GetDutyCycle()) {
     // device temp is not timesynced so don't add it to the list of signals
     device_temp_.SetUpdateFrequency(kCANUpdateFreqHz);
 
@@ -143,6 +144,9 @@
 
     position_.SetUpdateFrequency(kCANUpdateFreqHz);
     signals->push_back(&position_);
+
+    duty_cycle_.SetUpdateFrequency(kCANUpdateFreqHz);
+    signals->push_back(&duty_cycle_);
   }
 
   void PrintConfigs() {
@@ -226,6 +230,7 @@
     builder.add_supply_voltage(supply_voltage());
     builder.add_supply_current(supply_current());
     builder.add_torque_current(torque_current());
+    builder.add_duty_cycle(duty_cycle());
 
     double invert =
         (inverted_ ==
@@ -244,6 +249,7 @@
   float supply_voltage() const { return supply_voltage_.GetValue().value(); }
   float supply_current() const { return supply_current_.GetValue().value(); }
   float torque_current() const { return torque_current_.GetValue().value(); }
+  float duty_cycle() const { return duty_cycle_.GetValue().value(); }
   float position() const { return position_.GetValue().value(); }
 
   // returns the monotonic timestamp of the latest timesynced reading in the
@@ -269,6 +275,8 @@
   ctre::phoenixpro::StatusSignalValue<units::current::ampere_t> supply_current_,
       torque_current_;
   ctre::phoenixpro::StatusSignalValue<units::angle::turn_t> position_;
+  ctre::phoenixpro::StatusSignalValue<units::dimensionless::scalar_t>
+      duty_cycle_;
 };
 
 class CANSensorReader {
@@ -359,6 +367,7 @@
       roller_falcon_data.supply_voltage = roller_falcon_->supply_voltage();
       roller_falcon_data.device_temp = roller_falcon_->device_temp();
       roller_falcon_data.position = -roller_falcon_->position();
+      roller_falcon_data.duty_cycle = roller_falcon_->duty_cycle();
       roller_falcon_data_ =
           std::make_optional<superstructure::CANFalconT>(roller_falcon_data);
     }