Merge "Add a segment selector to ArmUI"
diff --git a/WORKSPACE b/WORKSPACE
index dd184d5..9bb5f38 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -99,14 +99,10 @@
 
 http_archive(
     name = "rules_pkg",
-    patch_args = ["-p1"],
-    patches = [
-        "//third_party:rules_pkg/0001-Fix-tree-artifacts.patch",
-    ],
-    sha256 = "62eeb544ff1ef41d786e329e1536c1d541bb9bcad27ae984d57f18f314018e66",
+    sha256 = "8c20f74bca25d2d442b327ae26768c02cf3c99e93fad0381f32be9aab1967675",
     urls = [
-        "https://mirror.bazel.build/github.com/bazelbuild/rules_pkg/releases/download/0.6.0/rules_pkg-0.6.0.tar.gz",
-        "https://github.com/bazelbuild/rules_pkg/releases/download/0.6.0/rules_pkg-0.6.0.tar.gz",
+        "https://mirror.bazel.build/github.com/bazelbuild/rules_pkg/releases/download/0.8.1/rules_pkg-0.8.1.tar.gz",
+        "https://github.com/bazelbuild/rules_pkg/releases/download/0.8.1/rules_pkg-0.8.1.tar.gz",
     ],
 )
 
@@ -1583,3 +1579,19 @@
     strip_prefix = "tensorflow-bazel",
     url = "https://www.frc971.org/Build-Dependencies/tensorflow-2.8.0.tar.gz",
 )
+
+http_archive(
+    name = "julia",
+    build_file = "//third_party:julia/julia.BUILD",
+    patch_cmds = [
+        "echo 'LIB_SYMLINKS = {' > files.bzl",
+        '''find lib/ -type l -exec bash -c 'echo "\\"{}\\": \\"$(readlink {})\\","' \\; | sort >> files.bzl''',
+        "echo '}' >> files.bzl",
+        "echo 'LIBS = [' >> files.bzl",
+        '''find lib/ -type f -exec bash -c 'echo "\\"{}\\","' \\; | sort >> files.bzl''',
+        "echo ']' >> files.bzl",
+    ],
+    sha256 = "e71a24816e8fe9d5f4807664cbbb42738f5aa9fe05397d35c81d4c5d649b9d05",
+    strip_prefix = "julia-1.8.5",
+    url = "https://julialang-s3.julialang.org/bin/linux/x64/1.8/julia-1.8.5-linux-x86_64.tar.gz",
+)
diff --git a/frc971/vision/foxglove_image_converter_lib.cc b/frc971/vision/foxglove_image_converter_lib.cc
index f5ecb40..920eaf7 100644
--- a/frc971/vision/foxglove_image_converter_lib.cc
+++ b/frc971/vision/foxglove_image_converter_lib.cc
@@ -3,7 +3,7 @@
 #include <opencv2/imgcodecs.hpp>
 #include <opencv2/imgproc.hpp>
 
-DEFINE_int32(jpeg_quality, 95,
+DEFINE_int32(jpeg_quality, 60,
              "Compression quality of JPEGs, 0-100; lower numbers mean lower "
              "quality and resulting image sizes.");
 
diff --git a/frc971/vision/foxglove_image_converter_test.cc b/frc971/vision/foxglove_image_converter_test.cc
index e027de2..7a3f786 100644
--- a/frc971/vision/foxglove_image_converter_test.cc
+++ b/frc971/vision/foxglove_image_converter_test.cc
@@ -6,6 +6,8 @@
 #include "aos/testing/tmpdir.h"
 #include "gtest/gtest.h"
 
+DECLARE_int32(jpeg_quality);
+
 namespace frc971::vision {
 std::ostream &operator<<(std::ostream &os, ImageCompression compression) {
   os << ExtensionForCompression(compression);
@@ -29,6 +31,10 @@
                    GetParam()),
         output_path_(absl::StrCat(aos::testing::TestTmpDir(), "/test.",
                                   ExtensionForCompression(GetParam()))) {
+    // Because our test image for comparison was generated with a JPEG quality
+    // of 95, we need to use that for the test to work. This also protects the
+    // tests against future changes to the default JPEG quality.
+    FLAGS_jpeg_quality = 95;
     test_event_loop_->OnRun(
         [this]() { image_sender_.CheckOk(image_sender_.Send(camera_image_)); });
     test_event_loop_->MakeWatcher(
diff --git a/frc971/vision/target_mapper.cc b/frc971/vision/target_mapper.cc
index 01a8df0..dd332fc 100644
--- a/frc971/vision/target_mapper.cc
+++ b/frc971/vision/target_mapper.cc
@@ -7,6 +7,9 @@
 
 DEFINE_uint64(max_num_iterations, 100,
               "Maximum number of iterations for the ceres solver");
+DEFINE_double(distortion_noise_scalar, 1.0,
+              "Scale the target pose distortion factor by this when computing "
+              "the noise.");
 
 namespace frc971::vision {
 
@@ -101,36 +104,33 @@
 
   // Match consecutive detections
   ceres::examples::VectorOfConstraints target_constraints;
-  for (auto it = timestamped_target_detections.begin() + 1;
-       it < timestamped_target_detections.end(); it++) {
-    auto last_detection = *(it - 1);
+  for (auto detection = timestamped_target_detections.begin() + 1;
+       detection < timestamped_target_detections.end(); detection++) {
+    auto last_detection = detection - 1;
 
     // Skip two consecutive detections of the same target, because the solver
     // doesn't allow this
-    if (it->id == last_detection.id) {
+    if (detection->id == last_detection->id) {
       continue;
     }
 
     // Don't take into account constraints too far apart in time, because the
     // recording device could have moved too much
-    if ((it->time - last_detection.time) > max_dt) {
+    if ((detection->time - last_detection->time) > max_dt) {
       continue;
     }
 
-    auto confidence = ComputeConfidence(last_detection.time, it->time,
-                                        last_detection.distance_from_camera,
-                                        it->distance_from_camera);
+    auto confidence = ComputeConfidence(*last_detection, *detection);
     target_constraints.emplace_back(
-        ComputeTargetConstraint(last_detection, *it, confidence));
+        ComputeTargetConstraint(*last_detection, *detection, confidence));
   }
 
   return target_constraints;
 }
 
 TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
-    aos::distributed_clock::time_point start,
-    aos::distributed_clock::time_point end, double distance_from_camera_start,
-    double distance_from_camera_end) {
+    const TimestampedDetection &detection_start,
+    const TimestampedDetection &detection_end) {
   constexpr size_t kX = 0;
   constexpr size_t kY = 1;
   constexpr size_t kZ = 2;
@@ -153,7 +153,8 @@
     Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
 
     // Add uncertainty for robot position measurements from start to end
-    int iterations = (end - start) / frc971::controls::kLoopFrequency;
+    int iterations = (detection_end.time - detection_start.time) /
+                     frc971::controls::kLoopFrequency;
     P += static_cast<double>(iterations) * Q_odometry;
   }
 
@@ -171,8 +172,12 @@
     Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
 
     // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
-    P += Q_vision * std::pow(distance_from_camera_start, 2);
-    P += Q_vision * std::pow(distance_from_camera_end, 2);
+    P += Q_vision * std::pow(detection_start.distance_from_camera, 2) *
+         (1.0 +
+          FLAGS_distortion_noise_scalar * detection_start.distortion_factor);
+    P +=
+        Q_vision * std::pow(detection_end.distance_from_camera, 2) *
+        (1.0 + FLAGS_distortion_noise_scalar * detection_end.distortion_factor);
   }
 
   return P.inverse();
diff --git a/frc971/vision/target_mapper.h b/frc971/vision/target_mapper.h
index 9d943c9..3724832 100644
--- a/frc971/vision/target_mapper.h
+++ b/frc971/vision/target_mapper.h
@@ -111,6 +111,8 @@
     // Horizontal distance from camera to target, used for confidence
     // calculation
     double distance_from_camera;
+    // A measure of how much distortion affected this detection from 0-1.
+    double distortion_factor;
     TargetMapper::TargetId id;
   };
 
@@ -128,9 +130,8 @@
   // detection between robot movement over the given time period. Ceres calls
   // this matrix the "information"
   static TargetMapper::ConfidenceMatrix ComputeConfidence(
-      aos::distributed_clock::time_point start,
-      aos::distributed_clock::time_point end, double distance_from_camera_start,
-      double distance_from_camera_end);
+      const TimestampedDetection &detection_start,
+      const TimestampedDetection &detection_end);
 
  private:
   // Computes the constraint between the start and end pose of the targets: the
diff --git a/frc971/vision/target_mapper_test.cc b/frc971/vision/target_mapper_test.cc
index 271f787..cd7d18b 100644
--- a/frc971/vision/target_mapper_test.cc
+++ b/frc971/vision/target_mapper_test.cc
@@ -95,12 +95,28 @@
 // Assumes camera and robot origin are the same
 DataAdapter::TimestampedDetection MakeTimestampedDetection(
     aos::distributed_clock::time_point time, Eigen::Affine3d H_robot_target,
-    TargetMapper::TargetId id) {
+    TargetMapper::TargetId id, double distortion_factor = 0.001) {
   auto target_pose = PoseUtils::Affine3dToPose3d(H_robot_target);
   return DataAdapter::TimestampedDetection{
-      time, H_robot_target,
-      std::sqrt(std::pow(target_pose.p(0), 2) + std::pow(target_pose.p(1), 2)),
-      id};
+      .time = time,
+      .H_robot_target = H_robot_target,
+      .distance_from_camera = target_pose.p.norm(),
+      .distortion_factor = distortion_factor,
+      .id = id};
+}
+
+DataAdapter::TimestampedDetection MakeTimestampedDetectionForConfidence(
+    aos::distributed_clock::time_point time, TargetMapper::TargetId id,
+    double distance_from_camera, double distortion_factor) {
+  auto target_pose = ceres::examples::Pose3d{
+      .p = Eigen::Vector3d(distance_from_camera, 0.0, 0.0),
+      .q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0)};
+  return DataAdapter::TimestampedDetection{
+      .time = time,
+      .H_robot_target = PoseUtils::Pose3dToAffine3d(target_pose),
+      .distance_from_camera = target_pose.p.norm(),
+      .distortion_factor = distortion_factor,
+      .id = id};
 }
 
 bool TargetIsInView(TargetMapper::TargetPose target_detection) {
@@ -170,17 +186,25 @@
   // Check the confidence matrices. Don't check the actual values
   // in case the constants change, just check that the confidence of contraints
   // decreases as time period or distances from camera increase.
+
+  constexpr size_t kIdStart = 0;
+  constexpr size_t kIdEnd = 1;
+
   {
     // Vary time period
     constexpr double kDistanceStart = 0.5;
     constexpr double kDistanceEnd = 2.0;
+    constexpr double kDistortionFactor = 0.001;
 
     TargetMapper::ConfidenceMatrix last_confidence =
         TargetMapper::ConfidenceMatrix::Zero();
     for (size_t dt = 0; dt < 15; dt++) {
       TargetMapper::ConfidenceMatrix confidence =
-          DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(dt),
-                                         kDistanceStart, kDistanceEnd);
+          DataAdapter::ComputeConfidence(
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(dt), kIdEnd, kDistanceEnd, kDistortionFactor));
 
       if (dt != 0) {
         // Confidence only decreases every 5ms (control loop period)
@@ -198,13 +222,19 @@
     // Vary distance at start
     constexpr int kDt = 3;
     constexpr double kDistanceEnd = 1.5;
+    constexpr double kDistortionFactor = 0.001;
+
     TargetMapper::ConfidenceMatrix last_confidence =
         TargetMapper::ConfidenceMatrix::Zero();
     for (double distance_start = 0.0; distance_start < 3.0;
          distance_start += 0.5) {
       TargetMapper::ConfidenceMatrix confidence =
-          DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(kDt),
-                                         distance_start, kDistanceEnd);
+          DataAdapter::ComputeConfidence(
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(0), kIdStart, distance_start, kDistortionFactor),
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(kDt), kIdEnd, kDistanceEnd, kDistortionFactor));
+
       if (distance_start != 0.0) {
         EXPECT_CONFIDENCE_GT(last_confidence, confidence);
       }
@@ -216,18 +246,48 @@
     // Vary distance at end
     constexpr int kDt = 2;
     constexpr double kDistanceStart = 2.5;
+    constexpr double kDistortionFactor = 0.001;
+
     TargetMapper::ConfidenceMatrix last_confidence =
         TargetMapper::ConfidenceMatrix::Zero();
     for (double distance_end = 0.0; distance_end < 3.0; distance_end += 0.5) {
       TargetMapper::ConfidenceMatrix confidence =
-          DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(kDt),
-                                         kDistanceStart, distance_end);
+          DataAdapter::ComputeConfidence(
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(kDt), kIdEnd, distance_end, kDistortionFactor));
+
       if (distance_end != 0.0) {
         EXPECT_CONFIDENCE_GT(last_confidence, confidence);
       }
       last_confidence = confidence;
     }
   }
+
+  {
+    // Vary distortion factor
+    constexpr int kDt = 2;
+    constexpr double kDistanceStart = 2.5;
+    constexpr double kDistanceEnd = 1.5;
+
+    TargetMapper::ConfidenceMatrix last_confidence =
+        TargetMapper::ConfidenceMatrix::Zero();
+    for (double distortion_factor = 0.0; distortion_factor <= 1.0;
+         distortion_factor += 0.01) {
+      TargetMapper::ConfidenceMatrix confidence =
+          DataAdapter::ComputeConfidence(
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(0), kIdStart, kDistanceStart, distortion_factor),
+              MakeTimestampedDetectionForConfidence(
+                  TimeInMs(kDt), kIdEnd, kDistanceEnd, distortion_factor));
+
+      if (distortion_factor != 0.0) {
+        EXPECT_CONFIDENCE_GT(last_confidence, confidence);
+      }
+      last_confidence = confidence;
+    }
+  }
 }
 
 TEST(DataAdapterTest, MatchTargetDetections) {
@@ -386,10 +446,18 @@
       target_detection.pose.q.y() += dist(generator_) * kNoiseScaleOrientation;
       target_detection.pose.q.z() += dist(generator_) * kNoiseScaleOrientation;
 
+      // Get most distortion factors close to zero, but have a few outliers
+      const std::vector<double> kDistortionFactorIntervals = {0.0, 0.01, 1.0};
+      const std::vector<double> kDistortionFactorWeights = {0.9, 0.1};
+      std::piecewise_constant_distribution<double> distortion_factor_dist(
+          kDistortionFactorIntervals.begin(), kDistortionFactorIntervals.end(),
+          kDistortionFactorWeights.begin());
+      double distortion_factor = distortion_factor_dist(generator_);
+
       auto time_point = TimeInMs(t);
       return MakeTimestampedDetection(
           time_point, PoseUtils::Pose3dToAffine3d(target_detection.pose),
-          target_detection.id);
+          target_detection.id, distortion_factor);
     }
 
     return std::nullopt;
diff --git a/scouting/DriverRank/BUILD b/scouting/DriverRank/BUILD
index e82fbfb..0e8c8d5 100644
--- a/scouting/DriverRank/BUILD
+++ b/scouting/DriverRank/BUILD
@@ -1,3 +1,5 @@
+load("@rules_pkg//:pkg.bzl", "pkg_deb", "pkg_tar")
+
 filegroup(
     name = "driver_rank_script",
     srcs = [
@@ -5,3 +7,57 @@
     ],
     visibility = ["//scouting:__subpackages__"],
 )
+
+pkg_tar(
+    name = "julia_runtime",
+    package_dir = "opt/frc971/julia_runtime",
+    deps = [
+        "@julia//:runtime",
+    ],
+)
+
+pkg_tar(
+    name = "julia_manifest",
+    srcs = [
+        "Manifest.toml",
+        "Project.toml",
+        "activate.jl",
+    ],
+    package_dir = "opt/frc971/julia_manifest",
+)
+
+pkg_tar(
+    name = "julia_files",
+    deps = [
+        ":julia_manifest",
+        ":julia_runtime",
+    ],
+)
+
+pkg_deb(
+    name = "frc971-scouting-julia",
+    architecture = "amd64",
+    data = ":julia_files",
+    description = "The Julia files for the FRC971 scouting web server.",
+    maintainer = "frc971@frc971.org",
+    package = "frc971-scouting-julia",
+    postinst = "postinst",
+    version = "1",
+)
+
+py_binary(
+    name = "deploy",
+    srcs = [
+        "deploy.py",
+    ],
+    args = [
+        "--deb",
+        "$(location :frc971-scouting-julia)",
+    ],
+    data = [
+        ":frc971-scouting-julia",
+    ],
+    deps = [
+        "//scouting/deploy",
+    ],
+)
diff --git a/scouting/DriverRank/README.md b/scouting/DriverRank/README.md
new file mode 100644
index 0000000..b744755
--- /dev/null
+++ b/scouting/DriverRank/README.md
@@ -0,0 +1,15 @@
+# Driver ranking parsing script
+
+This directory contains the script that parses the raw data that the scouts
+collect on driver rankings and gives each team a score.
+
+## Deployment
+
+Whenever the Julia environment is set up for the first time or whenever the
+dependencies are updated, the Julia package needs to be redeployed. This is a
+separate step from the scouting server deployment because the Julia runtime is
+huge.
+
+```console
+$ bazel run //scouting/DriverRank:deploy -- --host scouting
+```
diff --git a/scouting/DriverRank/activate.jl b/scouting/DriverRank/activate.jl
new file mode 100644
index 0000000..741d05d
--- /dev/null
+++ b/scouting/DriverRank/activate.jl
@@ -0,0 +1,4 @@
+# A small helper to install all the dependencies on the scouting server.
+using Pkg
+Pkg.activate(ARGS[1])
+Pkg.instantiate()
diff --git a/scouting/DriverRank/deploy.py b/scouting/DriverRank/deploy.py
new file mode 100644
index 0000000..6e88edf
--- /dev/null
+++ b/scouting/DriverRank/deploy.py
@@ -0,0 +1,6 @@
+import sys
+
+from org_frc971.scouting.deploy.deploy import main
+
+if __name__ == "__main__":
+    sys.exit(main(sys.argv))
diff --git a/scouting/DriverRank/postinst b/scouting/DriverRank/postinst
new file mode 100644
index 0000000..3c21b2b
--- /dev/null
+++ b/scouting/DriverRank/postinst
@@ -0,0 +1,11 @@
+#!/bin/bash
+
+set -o errexit
+set -o nounset
+set -o pipefail
+
+export PATH="/opt/frc971/julia_runtime/bin:${PATH}"
+export JULIA_DEPOT_PATH=/var/frc971/scouting/julia_depot/
+export JULIA_PROJECT=/opt/frc971/julia_manifest
+
+julia /opt/frc971/julia_manifest/activate.jl /opt/frc971/julia_manifest
diff --git a/scouting/DriverRank/src/DriverRank.jl b/scouting/DriverRank/src/DriverRank.jl
old mode 100644
new mode 100755
index c99be1f..39ac95e
--- a/scouting/DriverRank/src/DriverRank.jl
+++ b/scouting/DriverRank/src/DriverRank.jl
@@ -1,3 +1,5 @@
+#!/usr/bin/env julia
+
 module DriverRank
 
 using CSV
@@ -100,9 +102,11 @@
     return result
 end
 
-function rank()
-    # TODO(phil): Make the input path configurable.
-    df = DataFrame(CSV.File("./data/2022_madtown.csv"))
+function rank(
+    input_csv::String,
+    output_csv::String,
+)
+    df = DataFrame(CSV.File(input_csv))
 
     rank1 = "Rank 1 (best)"
     rank2 = "Rank 2"
@@ -133,10 +137,18 @@
             :score=>Optim.minimizer(res),
         ) |>
         x -> sort!(x, [:score], rev=true)
-    # TODO(phil): Save the output to a CSV file.
-    show(ranking_points, allrows=true)
+
+    # Uncomment to print the results on the console as well.
+    #show(ranking_points, allrows=true)
+
+    CSV.write(output_csv, ranking_points)
 end
 
 export rank
 
+# Run the program if this script is being executed from the command line.
+if abspath(PROGRAM_FILE) == @__FILE__
+    rank(ARGS[1], ARGS[2])
+end
+
 end # module
diff --git a/scouting/deploy/BUILD b/scouting/deploy/BUILD
index 2bf4b4e..c8f68c4 100644
--- a/scouting/deploy/BUILD
+++ b/scouting/deploy/BUILD
@@ -23,8 +23,8 @@
     # So we work around it by manually adding some symlinks that let us pretend
     # that we're at the root of the runfiles tree.
     symlinks = {
-        "opt/frc971/scouting_server/org_frc971": ".",
-        "opt/frc971/scouting_server/bazel_tools": "external/bazel_tools",
+        "org_frc971": ".",
+        "bazel_tools": "external/bazel_tools",
     },
 )
 
@@ -42,6 +42,9 @@
     name = "frc971-scouting-server",
     architecture = "amd64",
     data = ":deploy_tar",
+    depends = [
+        "frc971-scouting-julia",
+    ],
     description = "The FRC971 scouting web server.",
     # TODO(phil): What's a good email address for this?
     maintainer = "frc971@frc971.org",
@@ -66,4 +69,5 @@
     data = [
         ":frc971-scouting-server",
     ],
+    visibility = ["//scouting/DriverRank:__pkg__"],
 )
diff --git a/scouting/deploy/deploy.py b/scouting/deploy/deploy.py
index f947398..61c0481 100644
--- a/scouting/deploy/deploy.py
+++ b/scouting/deploy/deploy.py
@@ -47,6 +47,8 @@
                 "-c 'create schema public;'",
                 # List all tables as a sanity check.
                 "-c '\dt'",
+                # Make sure we make the visualizations accessible.
+                "-c 'GRANT ALL ON SCHEMA public TO tableau;'",
                 "postgres\"",
             ]),
             shell=True,
diff --git a/scouting/deploy/scouting.service b/scouting/deploy/scouting.service
index 5aa64b0..94582cd 100644
--- a/scouting/deploy/scouting.service
+++ b/scouting/deploy/scouting.service
@@ -8,6 +8,11 @@
 Type=simple
 WorkingDirectory=/opt/frc971/scouting_server
 Environment=RUNFILES_DIR=/opt/frc971/scouting_server
+# Add "julia" to the PATH.
+Environment=PATH=/opt/frc971/scouting/julia_runtime/bin:/usr/local/bin:/usr/bin:/bin
+# Use the Julia cache set up by the frc971-scouting-julia package.
+Environment=JULIA_DEPOT_PATH=/var/frc971/scouting/julia_depot/
+Environment=JULIA_PROJECT=/opt/frc971/julia_manifest
 ExecStart=/opt/frc971/scouting_server/scouting/scouting \
     -port 8080 \
     -db_config /var/frc971/scouting/db_config.json \
diff --git a/scouting/webserver/BUILD b/scouting/webserver/BUILD
index 934aff1..934b50a 100644
--- a/scouting/webserver/BUILD
+++ b/scouting/webserver/BUILD
@@ -9,6 +9,7 @@
     deps = [
         "//scouting/db",
         "//scouting/scraping/background",
+        "//scouting/webserver/driver_ranking",
         "//scouting/webserver/match_list",
         "//scouting/webserver/rankings",
         "//scouting/webserver/requests",
diff --git a/scouting/webserver/driver_ranking/driver_ranking.go b/scouting/webserver/driver_ranking/driver_ranking.go
index 005078f..82e34e1 100644
--- a/scouting/webserver/driver_ranking/driver_ranking.go
+++ b/scouting/webserver/driver_ranking/driver_ranking.go
@@ -119,7 +119,8 @@
 	// database.
 	outputRecords, err := readFromCsv(outputCsvFile)
 
-	for _, record := range outputRecords {
+	// Skip the first row since those are the column labels.
+	for _, record := range outputRecords[1:] {
 		score, err := strconv.ParseFloat(record[1], 32)
 		if err != nil {
 			log.Println("Failed to parse score for team ", record[0], ": ", record[1], ": ", err)
diff --git a/scouting/webserver/driver_ranking/fake_driver_rank_script.py b/scouting/webserver/driver_ranking/fake_driver_rank_script.py
index 8f72267..c9a96eb 100644
--- a/scouting/webserver/driver_ranking/fake_driver_rank_script.py
+++ b/scouting/webserver/driver_ranking/fake_driver_rank_script.py
@@ -18,6 +18,7 @@
 ]
 
 OUTPUT = [
+    ("team", "score"),
     ("1234", "1.5"),
     ("1235", "2.75"),
     ("1236", "4.0"),
diff --git a/scouting/webserver/main.go b/scouting/webserver/main.go
index 1811b7f..4752cf4 100644
--- a/scouting/webserver/main.go
+++ b/scouting/webserver/main.go
@@ -15,6 +15,7 @@
 
 	"github.com/frc971/971-Robot-Code/scouting/db"
 	"github.com/frc971/971-Robot-Code/scouting/scraping/background"
+	"github.com/frc971/971-Robot-Code/scouting/webserver/driver_ranking"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/match_list"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/rankings"
 	"github.com/frc971/971-Robot-Code/scouting/webserver/requests"
@@ -139,6 +140,13 @@
 		rankings.GetRankings(database, 0, "", *blueAllianceConfigPtr)
 	})
 
+	driverRankingParser := background.BackgroundScraper{}
+	driverRankingParser.Start(func() {
+		// Specify "" as the script path here so that the default is
+		// used.
+		driver_ranking.GenerateFullDriverRanking(database, "")
+	})
+
 	// Block until the user hits Ctrl-C.
 	sigint := make(chan os.Signal, 1)
 	signal.Notify(sigint, syscall.SIGINT)
@@ -149,6 +157,7 @@
 	fmt.Println("Shutting down.")
 	scoutingServer.Stop()
 	rankingsScraper.Stop()
+	driverRankingParser.Stop()
 	matchListScraper.Stop()
 	fmt.Println("Successfully shut down.")
 }
diff --git a/third_party/julia/julia.BUILD b/third_party/julia/julia.BUILD
new file mode 100644
index 0000000..94988ca
--- /dev/null
+++ b/third_party/julia/julia.BUILD
@@ -0,0 +1,18 @@
+load("@rules_pkg//:pkg.bzl", "pkg_tar")
+load(":files.bzl", "LIB_SYMLINKS", "LIBS")
+
+pkg_tar(
+    name = "runtime",
+    srcs = LIBS + [
+        "bin/julia",
+    ] + glob([
+        "share/julia/**/*.jl",
+        "share/julia/**/*.toml",
+        "include/julia/**/*",
+    ], exclude = [
+        "**/test/**",
+    ]),
+    symlinks = LIB_SYMLINKS,
+    strip_prefix = "external/julia",
+    visibility = ["//visibility:public"],
+)
diff --git a/third_party/rules_pkg/0001-Fix-tree-artifacts.patch b/third_party/rules_pkg/0001-Fix-tree-artifacts.patch
deleted file mode 100644
index 567aba7..0000000
--- a/third_party/rules_pkg/0001-Fix-tree-artifacts.patch
+++ /dev/null
@@ -1,28 +0,0 @@
-From d654cc64ae71366ea82ac492106e9b2c8fa532d5 Mon Sep 17 00:00:00 2001
-From: Philipp Schrader <philipp.schrader@gmail.com>
-Date: Thu, 10 Mar 2022 23:25:21 -0800
-Subject: [PATCH] Fix tree artifacts
-
-For some reason the upstream code strips the directory names from the
-`babel()` rule that we use. This patch makes it so the directory is
-not stripped.  This makes runfiles layout in the tarball match the
-runfiles layout in `bazel-bin`.
----
- pkg/pkg.bzl | 4 ++--
- 1 file changed, 2 insertions(+), 2 deletions(-)
-
-diff --git a/pkg/pkg.bzl b/pkg/pkg.bzl
-index d7adbbc..a241b26 100644
---- a/pkg/pkg.bzl
-+++ b/pkg/pkg.bzl
-@@ -157,8 +157,8 @@ def _pkg_tar_impl(ctx):
-                     # Tree artifacts need a name, but the name is never really
-                     # the important part. The likely behavior people want is
-                     # just the content, so we strip the directory name.
--                    dest = "/".join(d_path.split("/")[0:-1])
--                    add_tree_artifact(content_map, dest, f, src.label)
-+                    #dest = "/".join(d_path.split("/")[0:-1])
-+                    add_tree_artifact(content_map, d_path, f, src.label)
-                 else:
-                     # Note: This extra remap is the bottleneck preventing this
-                     # large block from being a utility method as shown below.
diff --git a/tools/dependency_rewrite b/tools/dependency_rewrite
index 7e9e1de..16fe927 100644
--- a/tools/dependency_rewrite
+++ b/tools/dependency_rewrite
@@ -9,6 +9,7 @@
 rewrite static.rust-lang.org/(.*) software.frc971.org/Build-Dependencies/static.rust-lang.org/$1
 rewrite storage.googleapis.com/(.*) software.frc971.org/Build-Dependencies/storage.googleapis.com/$1
 rewrite files.pythonhosted.org/(.*) software.frc971.org/Build-Dependencies/files.pythonhosted.org/$1
+rewrite julialang-s3.julialang.org/(.*) software.frc971.org/Build-Dependencies/julialang-s3.julialang.org/$1
 rewrite devsite.ctr-electronics.com/(.*) software.frc971.org/Build-Dependencies/devsite.ctr-electronics.com/$1
 rewrite www.openssl.org/(.*) software.frc971.org/Build-Dependencies/www.openssl.org/$1
 rewrite zlib.net/(.*) software.frc971.org/Build-Dependencies/zlib.net/$1
diff --git a/y2023/constants/971.json b/y2023/constants/971.json
index 16681fb..2f91d1b 100644
--- a/y2023/constants/971.json
+++ b/y2023/constants/971.json
@@ -1,7 +1,7 @@
 {
   "cameras": [
     {
-      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-02-22.json' %}
+      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-03-05.json' %}
     },
     {
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-971-2_cam-23-06_ext_2023-02-22.json' %}
diff --git a/y2023/constants/9971.json b/y2023/constants/9971.json
index a4eaff4..4795d61 100644
--- a/y2023/constants/9971.json
+++ b/y2023/constants/9971.json
@@ -4,7 +4,7 @@
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-9971-1_cam-23-09_ext_2023-03-05.json' %}
     },
     {
-      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-05.json' %}
+      "calibration": {% include 'y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-08.json' %}
     },
     {
       "calibration": {% include 'y2023/vision/calib_files/calibration_pi-9971-3_cam-23-11_ext_2023-03-05.json' %}
diff --git a/y2023/control_loops/drivetrain/BUILD b/y2023/control_loops/drivetrain/BUILD
index 521fc09..063e972 100644
--- a/y2023/control_loops/drivetrain/BUILD
+++ b/y2023/control_loops/drivetrain/BUILD
@@ -162,6 +162,7 @@
         "//y2023/constants:constants_fbs",
         "//y2023/control_loops/superstructure:superstructure_position_fbs",
         "//y2023/control_loops/superstructure:superstructure_status_fbs",
+        "//y2023/vision:game_pieces_fbs",
     ],
 )
 
diff --git a/y2023/control_loops/drivetrain/target_selector.cc b/y2023/control_loops/drivetrain/target_selector.cc
index aacfbbf..16a0090 100644
--- a/y2023/control_loops/drivetrain/target_selector.cc
+++ b/y2023/control_loops/drivetrain/target_selector.cc
@@ -3,6 +3,7 @@
 #include "aos/containers/sized_array.h"
 #include "frc971/shooter_interpolation/interpolation.h"
 #include "y2023/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2023/vision/game_pieces_generated.h"
 
 namespace y2023::control_loops::drivetrain {
 namespace {
@@ -15,7 +16,8 @@
     : joystick_state_fetcher_(
           event_loop->MakeFetcher<aos::JoystickState>("/aos")),
       hint_fetcher_(event_loop->MakeFetcher<TargetSelectorHint>("/drivetrain")),
-      superstructure_status_fetcher_(event_loop->MakeFetcher<superstructure::Status>("/superstructure")),
+      superstructure_status_fetcher_(
+          event_loop->MakeFetcher<superstructure::Status>("/superstructure")),
       status_sender_(
           event_loop->MakeSender<TargetSelectorStatus>("/drivetrain")),
       constants_fetcher_(event_loop) {
@@ -33,12 +35,14 @@
             LateralOffsetForTimeOfFlight(msg.cone_position());
       });
 
-  event_loop->AddPhasedLoop([this](int){
-      auto builder = status_sender_.MakeBuilder();
-      auto status_builder = builder.MakeBuilder<TargetSelectorStatus>();
-      status_builder.add_game_piece_position(game_piece_position_);
-      builder.CheckOk(builder.Send(status_builder.Finish()));
-      }, std::chrono::milliseconds(100));
+  event_loop->AddPhasedLoop(
+      [this](int) {
+        auto builder = status_sender_.MakeBuilder();
+        auto status_builder = builder.MakeBuilder<TargetSelectorStatus>();
+        status_builder.add_game_piece_position(game_piece_position_);
+        builder.CheckOk(builder.Send(status_builder.Finish()));
+      },
+      std::chrono::milliseconds(100));
 }
 
 void TargetSelector::UpdateAlliance() {
@@ -180,10 +184,13 @@
   superstructure_status_fetcher_.Fetch();
   if (superstructure_status_fetcher_.get() != nullptr) {
     switch (superstructure_status_fetcher_->game_piece()) {
-      case superstructure::GamePiece::NONE:
-      case superstructure::GamePiece::CUBE:
+      case vision::Class::NONE:
+      case vision::Class::CUBE:
         return 0.0;
-      case superstructure::GamePiece::CONE:
+      case vision::Class::CONE_UP:
+        // execute logic below.
+        break;
+      case vision::Class::CONE_DOWN:
         // execute logic below.
         break;
     }
diff --git a/y2023/control_loops/python/graph_edit.py b/y2023/control_loops/python/graph_edit.py
index 82961fb..287c5b0 100644
--- a/y2023/control_loops/python/graph_edit.py
+++ b/y2023/control_loops/python/graph_edit.py
@@ -13,7 +13,7 @@
 gi.require_version('Gtk', '3.0')
 from gi.repository import Gdk, Gtk
 import cairo
-from y2023.control_loops.python.graph_tools import to_theta, to_xy, alpha_blend, shift_angles
+from y2023.control_loops.python.graph_tools import to_theta, to_xy, alpha_blend, shift_angles, get_xy
 from y2023.control_loops.python.graph_tools import l1, l2, joint_center
 from y2023.control_loops.python.graph_tools import DRIVER_CAM_POINTS
 from y2023.control_loops.python import graph_paths
@@ -418,6 +418,7 @@
             random.shuffle(color)
             set_color(cr, Color(color[0], color[1], color[2]))
             self.segments[i].DrawTo(cr, self.theta_version)
+
             with px(cr):
                 cr.stroke()
 
@@ -425,6 +426,19 @@
         color = [0, 0, 0]
         set_color(cr, Color(color[0], color[1], color[2]))
         self.segments[self.index].DrawTo(cr, self.theta_version)
+
+        control1 = get_xy(self.segments[self.index].control1)
+        control2 = get_xy(self.segments[self.index].control2)
+
+        if self.theta_version:
+            control1 = shift_angles(self.segments[self.index].control1)
+            control2 = shift_angles(self.segments[self.index].control2)
+
+        cr.move_to(control1[0] + 0.02, control1[1])
+        cr.arc(control1[0], control1[1], 0.02, 0, 2.0 * np.pi)
+        cr.move_to(control2[0] + 0.02, control2[1])
+        cr.arc(control2[0], control2[1], 0.02, 0, 2.0 * np.pi)
+
         with px(cr):
             cr.stroke()
 
diff --git a/y2023/control_loops/python/graph_paths.py b/y2023/control_loops/python/graph_paths.py
index f7571a6..12a8967 100644
--- a/y2023/control_loops/python/graph_paths.py
+++ b/y2023/control_loops/python/graph_paths.py
@@ -1,3 +1,5 @@
+import sys
+
 import numpy as np
 
 from y2023.control_loops.python.graph_tools import *
@@ -419,3 +421,26 @@
 back_points = []
 unnamed_segments = []
 segments = named_segments + unnamed_segments
+
+# This checks that all points are unique
+
+seen_segments = []
+
+for segment in segments:
+    # check for equality of the start and end values
+
+    if (segment.start.tolist(), segment.end.tolist()) in seen_segments:
+        print("Repeated value")
+        segment.Print(points)
+        sys.exit(1)
+    else:
+        seen_segments.append((segment.start.tolist(), segment.end.tolist()))
+
+seen_points = []
+
+for point in points:
+    if point in seen_points:
+        print(f"Repeated value {point}")
+        sys.exit(1)
+    else:
+        seen_points.append(point)
diff --git a/y2023/control_loops/superstructure/BUILD b/y2023/control_loops/superstructure/BUILD
index a4cb337..2700bbc 100644
--- a/y2023/control_loops/superstructure/BUILD
+++ b/y2023/control_loops/superstructure/BUILD
@@ -33,6 +33,7 @@
     deps = [
         "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops:profiled_subsystem_fbs",
+        "//y2023/vision:game_pieces_fbs",
     ],
 )
 
@@ -44,6 +45,7 @@
     deps = [
         "//frc971/control_loops:control_loops_ts_fbs",
         "//frc971/control_loops:profiled_subsystem_ts_fbs",
+        "//y2023/vision:game_pieces_ts_fbs",
     ],
 )
 
@@ -76,6 +78,7 @@
         "//aos/time",
         "//frc971/control_loops:control_loop",
         "//y2023:constants",
+        "//y2023/vision:game_pieces_fbs",
     ],
 )
 
@@ -145,6 +148,7 @@
         "//frc971/control_loops:team_number_test_environment",
         "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
         "//y2023/control_loops/superstructure/roll:roll_plants",
+        "//y2023/vision:game_pieces_fbs",
     ],
 )
 
diff --git a/y2023/control_loops/superstructure/arm/BUILD b/y2023/control_loops/superstructure/arm/BUILD
index 44b2aac..39e549b 100644
--- a/y2023/control_loops/superstructure/arm/BUILD
+++ b/y2023/control_loops/superstructure/arm/BUILD
@@ -22,6 +22,7 @@
         "//y2023/control_loops/superstructure/arm:arm_constants",
         "//y2023/control_loops/superstructure/arm:trajectory",
         "//y2023/control_loops/superstructure/roll:roll_plants",
+        "//y2023/vision:game_pieces_fbs",
     ],
 )
 
diff --git a/y2023/control_loops/superstructure/end_effector.cc b/y2023/control_loops/superstructure/end_effector.cc
index 287f0e7..4d5d43e 100644
--- a/y2023/control_loops/superstructure/end_effector.cc
+++ b/y2023/control_loops/superstructure/end_effector.cc
@@ -3,6 +3,7 @@
 #include "aos/events/event_loop.h"
 #include "aos/time/time.h"
 #include "frc971/control_loops/control_loop.h"
+#include "y2023/vision/game_pieces_generated.h"
 
 namespace y2023 {
 namespace control_loops {
@@ -12,7 +13,7 @@
 
 EndEffector::EndEffector()
     : state_(EndEffectorState::IDLE),
-      game_piece_(GamePiece::NONE),
+      game_piece_(vision::Class::NONE),
       timer_(aos::monotonic_clock::min_time),
       beambreak_(false) {}
 
@@ -25,16 +26,22 @@
   constexpr double kMinCurrent = 40.0;
   constexpr double kMaxConePosition = 0.92;
 
-  bool beambreak_status = (beambreak || (falcon_current > kMinCurrent &&
-                                         cone_position < kMaxConePosition));
-
   // Let them switch game pieces
-  if (roller_goal == RollerGoal::INTAKE_CONE) {
-    game_piece_ = GamePiece::CONE;
+  if (roller_goal == RollerGoal::INTAKE_CONE_UP) {
+    game_piece_ = vision::Class::CONE_UP;
+  } else if (roller_goal == RollerGoal::INTAKE_CONE_DOWN) {
+    game_piece_ = vision::Class::CONE_DOWN;
   } else if (roller_goal == RollerGoal::INTAKE_CUBE) {
-    game_piece_ = GamePiece::CUBE;
+    game_piece_ = vision::Class::CUBE;
   }
 
+  bool beambreak_status =
+      (((game_piece_ == vision::Class::CUBE ||
+         game_piece_ == vision::Class::CONE_UP) &&
+        beambreak) ||
+       ((game_piece_ == vision::Class::CONE_DOWN &&
+         falcon_current > kMinCurrent && cone_position < kMaxConePosition)));
+
   // Go into spitting if we were told to, no matter where we are
   if (roller_goal == RollerGoal::SPIT && state_ != EndEffectorState::SPITTING) {
     state_ = EndEffectorState::SPITTING;
@@ -47,7 +54,8 @@
   switch (state_) {
     case EndEffectorState::IDLE:
       // If idle and intake requested, intake
-      if (roller_goal == RollerGoal::INTAKE_CONE ||
+      if (roller_goal == RollerGoal::INTAKE_CONE_UP ||
+          roller_goal == RollerGoal::INTAKE_CONE_DOWN ||
           roller_goal == RollerGoal::INTAKE_CUBE ||
           roller_goal == RollerGoal::INTAKE_LAST) {
         state_ = EndEffectorState::INTAKING;
@@ -56,7 +64,8 @@
       break;
     case EndEffectorState::INTAKING:
       // If intaking and beam break is not triggered, keep intaking
-      if (roller_goal == RollerGoal::INTAKE_CONE ||
+      if (roller_goal == RollerGoal::INTAKE_CONE_UP ||
+          roller_goal == RollerGoal::INTAKE_CONE_DOWN ||
           roller_goal == RollerGoal::INTAKE_CUBE ||
           roller_goal == RollerGoal::INTAKE_LAST) {
         timer_ = timestamp;
@@ -72,7 +81,7 @@
         break;
       }
 
-      if (game_piece_ == GamePiece::CUBE) {
+      if (game_piece_ == vision::Class::CUBE) {
         *roller_voltage = kRollerCubeSuckVoltage();
       } else {
         *roller_voltage = kRollerConeSuckVoltage();
@@ -88,7 +97,7 @@
       break;
     case EndEffectorState::SPITTING:
       // If spit requested, spit
-      if (game_piece_ == GamePiece::CUBE) {
+      if (game_piece_ == vision::Class::CUBE) {
         *roller_voltage = kRollerCubeSpitVoltage();
       } else {
         *roller_voltage = kRollerConeSpitVoltage();
@@ -100,7 +109,7 @@
       } else if (timestamp > timer_ + constants::Values::kExtraSpittingTime()) {
         // Finished spitting
         state_ = EndEffectorState::IDLE;
-        game_piece_ = GamePiece::NONE;
+        game_piece_ = vision::Class::NONE;
       }
 
       break;
diff --git a/y2023/control_loops/superstructure/end_effector.h b/y2023/control_loops/superstructure/end_effector.h
index 14245c8..5ae96da 100644
--- a/y2023/control_loops/superstructure/end_effector.h
+++ b/y2023/control_loops/superstructure/end_effector.h
@@ -7,6 +7,7 @@
 #include "y2023/constants.h"
 #include "y2023/control_loops/superstructure/superstructure_goal_generated.h"
 #include "y2023/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2023/vision/game_pieces_generated.h"
 
 namespace y2023 {
 namespace control_loops {
@@ -26,12 +27,12 @@
                     double cone_position, bool beambreak,
                     double *intake_roller_voltage);
   EndEffectorState state() const { return state_; }
-  GamePiece game_piece() const { return game_piece_; }
+  vision::Class game_piece() const { return game_piece_; }
   void Reset();
 
  private:
   EndEffectorState state_;
-  GamePiece game_piece_;
+  vision::Class game_piece_;
 
   aos::monotonic_clock::time_point timer_;
 
diff --git a/y2023/control_loops/superstructure/superstructure_goal.fbs b/y2023/control_loops/superstructure/superstructure_goal.fbs
index ee99f1c..670351a 100644
--- a/y2023/control_loops/superstructure/superstructure_goal.fbs
+++ b/y2023/control_loops/superstructure/superstructure_goal.fbs
@@ -4,10 +4,11 @@
 
 enum RollerGoal: ubyte {
     IDLE = 0,
-    INTAKE_CONE = 1,
+    INTAKE_CONE_UP = 1,
     INTAKE_CUBE = 2,
     INTAKE_LAST = 3,
     SPIT = 4,
+    INTAKE_CONE_DOWN = 5,
 }
 
 table Goal {
diff --git a/y2023/control_loops/superstructure/superstructure_lib_test.cc b/y2023/control_loops/superstructure/superstructure_lib_test.cc
index ee440ed..e2524c1 100644
--- a/y2023/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2023/control_loops/superstructure/superstructure_lib_test.cc
@@ -562,10 +562,10 @@
 
 class SuperstructureBeambreakTest
     : public SuperstructureTest,
-      public ::testing::WithParamInterface<GamePiece> {
+      public ::testing::WithParamInterface<vision::Class> {
  public:
-  void SetBeambreak(GamePiece game_piece, bool status) {
-    if (game_piece == GamePiece::CONE) {
+  void SetBeambreak(vision::Class game_piece, bool status) {
+    if (game_piece == vision::Class::CONE_UP) {
       // TODO(milind): handle cone
     } else {
       superstructure_plant_.set_end_effector_cube_beam_break(status);
@@ -577,12 +577,20 @@
   SetEnabled(true);
   WaitUntilZeroed();
 
-  double spit_voltage =
-      (GetParam() == GamePiece::CUBE ? EndEffector::kRollerCubeSpitVoltage()
-                                     : EndEffector::kRollerConeSpitVoltage());
-  double suck_voltage =
-      (GetParam() == GamePiece::CUBE ? EndEffector::kRollerCubeSuckVoltage()
-                                     : EndEffector::kRollerConeSuckVoltage());
+  double spit_voltage = (GetParam() == vision::Class::CUBE
+                             ? EndEffector::kRollerCubeSpitVoltage()
+                             : EndEffector::kRollerConeSpitVoltage());
+  double suck_voltage = (GetParam() == vision::Class::CUBE
+                             ? EndEffector::kRollerCubeSuckVoltage()
+                             : EndEffector::kRollerConeSuckVoltage());
+
+  RollerGoal roller_goal = RollerGoal::INTAKE_CUBE;
+
+  if (GetParam() == vision::Class::CONE_DOWN) {
+    roller_goal = RollerGoal::INTAKE_CONE_DOWN;
+  } else if (GetParam() == vision::Class::CONE_UP) {
+    roller_goal = RollerGoal::INTAKE_CONE_UP;
+  }
 
   {
     auto builder = superstructure_goal_sender_.MakeBuilder();
@@ -591,9 +599,7 @@
 
     goal_builder.add_arm_goal_position(arm::NeutralIndex());
     goal_builder.add_trajectory_override(false);
-    goal_builder.add_roller_goal(GetParam() == GamePiece::CONE
-                                     ? RollerGoal::INTAKE_CONE
-                                     : RollerGoal::INTAKE_CUBE);
+    goal_builder.add_roller_goal(roller_goal);
 
     builder.CheckOk(builder.Send(goal_builder.Finish()));
   }
@@ -668,9 +674,7 @@
 
     goal_builder.add_arm_goal_position(arm::NeutralIndex());
     goal_builder.add_trajectory_override(false);
-    goal_builder.add_roller_goal(GetParam() == GamePiece::CONE
-                                     ? RollerGoal::INTAKE_CONE
-                                     : RollerGoal::INTAKE_CUBE);
+    goal_builder.add_roller_goal(roller_goal);
 
     builder.CheckOk(builder.Send(goal_builder.Finish()));
   }
@@ -757,7 +761,7 @@
   EXPECT_EQ(superstructure_output_fetcher_->roller_voltage(), 0.0);
   EXPECT_EQ(superstructure_status_fetcher_->end_effector_state(),
             EndEffectorState::IDLE);
-  EXPECT_EQ(superstructure_status_fetcher_->game_piece(), GamePiece::NONE);
+  EXPECT_EQ(superstructure_status_fetcher_->game_piece(), vision::Class::NONE);
 }
 
 // Tests that we don't freak out without a goal.
@@ -834,7 +838,7 @@
 
 // TODO(milind): add cone
 INSTANTIATE_TEST_SUITE_P(EndEffectorGoal, SuperstructureBeambreakTest,
-                         ::testing::Values(GamePiece::CUBE));
+                         ::testing::Values(vision::Class::CUBE));
 
 }  // namespace testing
 }  // namespace superstructure
diff --git a/y2023/control_loops/superstructure/superstructure_status.fbs b/y2023/control_loops/superstructure/superstructure_status.fbs
index 80a0d3d..5381b0a 100644
--- a/y2023/control_loops/superstructure/superstructure_status.fbs
+++ b/y2023/control_loops/superstructure/superstructure_status.fbs
@@ -1,4 +1,5 @@
 include "frc971/control_loops/control_loops.fbs";
+include "y2023/vision/game_pieces.fbs";
 include "frc971/control_loops/profiled_subsystem.fbs";
 
 namespace y2023.control_loops.superstructure;
@@ -76,12 +77,6 @@
   SPITTING = 3,
 }
 
-enum GamePiece : ubyte {
-  NONE = 0,
-  CONE = 1,
-  CUBE = 2,
-}
-
 table Status {
   // All subsystems know their location.
   zeroed:bool (id: 0);
@@ -94,7 +89,7 @@
   wrist:frc971.control_loops.AbsoluteEncoderProfiledJointStatus (id: 3);
 
   end_effector_state:EndEffectorState (id: 4);
-  game_piece:GamePiece (id: 5);
+  game_piece:vision.Class (id: 5);
 }
 
 root_type Status;
diff --git a/y2023/joystick_reader.cc b/y2023/joystick_reader.cc
index 43962dd..68fe6af 100644
--- a/y2023/joystick_reader.cc
+++ b/y2023/joystick_reader.cc
@@ -334,10 +334,10 @@
     std::optional<double> score_wrist_goal = std::nullopt;
 
     if (data.IsPressed(kGroundPickupConeUp) || data.IsPressed(kHPConePickup)) {
-      roller_goal = RollerGoal::INTAKE_CONE;
+      roller_goal = RollerGoal::INTAKE_CONE_UP;
       current_game_piece_ = GamePiece::CONE_UP;
     } else if (data.IsPressed(kGroundPickupConeDownBase)) {
-      roller_goal = RollerGoal::INTAKE_CONE;
+      roller_goal = RollerGoal::INTAKE_CONE_DOWN;
       current_game_piece_ = GamePiece::CONE_DOWN;
     } else if (data.IsPressed(kGroundPickupCube)) {
       roller_goal = RollerGoal::INTAKE_CUBE;
diff --git a/y2023/localizer/localizer.cc b/y2023/localizer/localizer.cc
index 3a6de93..ffc1df3 100644
--- a/y2023/localizer/localizer.cc
+++ b/y2023/localizer/localizer.cc
@@ -166,7 +166,7 @@
   }
 
   event_loop_->AddPhasedLoop([this](int) { SendOutput(); },
-                             std::chrono::milliseconds(5));
+                             std::chrono::milliseconds(20));
 
   event_loop_->MakeWatcher(
       "/drivetrain",
diff --git a/y2023/localizer/localizer_test.cc b/y2023/localizer/localizer_test.cc
index 947771f..57b9dd0 100644
--- a/y2023/localizer/localizer_test.cc
+++ b/y2023/localizer/localizer_test.cc
@@ -332,7 +332,9 @@
 // correctly.
 TEST_F(LocalizerTest, NominalSpinInPlace) {
   output_voltages_ << -1.0, 1.0;
-  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  // Go 1 ms over 2 sec to make sure we actually see relatively recent messages
+  // on each channel.
+  event_loop_factory_.RunFor(std::chrono::milliseconds(2001));
   CHECK(output_fetcher_.Fetch());
   CHECK(status_fetcher_.Fetch());
   // The two can be different because they may've been sent at different
diff --git a/y2023/vision/BUILD b/y2023/vision/BUILD
index e90b825..68ba833 100644
--- a/y2023/vision/BUILD
+++ b/y2023/vision/BUILD
@@ -1,4 +1,5 @@
 load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
 
 cc_binary(
     name = "camera_reader",
@@ -239,3 +240,10 @@
     target_compatible_with = ["@platforms//os:linux"],
     visibility = ["//visibility:public"],
 )
+
+flatbuffer_ts_library(
+    name = "game_pieces_ts_fbs",
+    srcs = ["game_pieces.fbs"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
diff --git a/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-02-22.json b/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-02-22.json
deleted file mode 100644
index b21da40..0000000
--- a/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-02-22.json
+++ /dev/null
@@ -1 +0,0 @@
-{ "node_name": "pi1", "team_number": 971, "intrinsics": [ 890.980713, 0.0, 619.298645, 0.0, 890.668762, 364.009766, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ -0.487722, 0.222354, 0.844207, 0.025116, 0.864934, -0.008067, 0.501821, -0.246003, 0.118392, 0.974933, -0.188387, 0.532497, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.449172, 0.252318, 0.000881, -0.000615, -0.082208 ], "calibration_timestamp": 1358501902915096335, "camera_id": "23-05" }
\ No newline at end of file
diff --git a/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-03-05.json b/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-03-05.json
new file mode 100644
index 0000000..f585519
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-971-1_cam-23-05_ext_2023-03-05.json
@@ -0,0 +1 @@
+{ "node_name": "pi1", "team_number": 971, "intrinsics": [ 890.980713, 0.0, 619.298645, 0.0, 890.668762, 364.009766, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ -0.487918, 0.221538, 0.844309, 0.190808, 0.866039, 0.00192, 0.499972, -0.218036, 0.109142, 0.97515, -0.192797, 0.544037, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.449172, 0.252318, 0.000881, -0.000615, -0.082208 ], "calibration_timestamp": 1358501902915096335, "camera_id": "23-05" }
\ No newline at end of file
diff --git a/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-05.json b/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-05.json
deleted file mode 100644
index 1a90acf..0000000
--- a/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-05.json
+++ /dev/null
@@ -1 +0,0 @@
-{ "node_name": "pi2", "team_number": 9971, "intrinsics": [ 894.002502, 0.0, 636.431335, 0.0, 893.723816, 377.069672, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ 0.838991, 0.208096, 0.502782, 0.218892, 0.515207, -0.006486, -0.857041, -0.023335, -0.175086, 0.978087, -0.112654, 0.663515, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.446659, 0.244189, 0.000632, 0.000171, -0.074849 ], "calibration_timestamp": 1358503360377380613, "camera_id": "23-10" }
\ No newline at end of file
diff --git a/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-08.json b/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-08.json
new file mode 100644
index 0000000..547d8d7
--- /dev/null
+++ b/y2023/vision/calib_files/calibration_pi-9971-2_cam-23-10_ext_2023-03-08.json
@@ -0,0 +1 @@
+{ "node_name": "pi2", "team_number": 9971, "intrinsics": [ 894.002502, 0.0, 636.431335, 0.0, 893.723816, 377.069672, 0.0, 0.0, 1.0 ], "fixed_extrinsics": { "data": [ 0.830467, 0.233602, 0.505721, 0.242226, 0.519225, 0.004294, -0.854627, -0.167586, -0.201814, 0.972323, -0.117727, 0.614872, 0.0, 0.0, 0.0, 1.0 ] }, "dist_coeffs": [ -0.446659, 0.244189, 0.000632, 0.000171, -0.074849 ], "calibration_timestamp": 1358503360377380613, "camera_id": "23-10" }
\ No newline at end of file
diff --git a/y2023/vision/game_pieces.cc b/y2023/vision/game_pieces.cc
index 868d5b0..0e2546f 100644
--- a/y2023/vision/game_pieces.cc
+++ b/y2023/vision/game_pieces.cc
@@ -1,44 +1,96 @@
 #include "y2023/vision/game_pieces.h"
 
+#include <ctime>
+
 #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");
+
 namespace y2023 {
 namespace vision {
 GamePiecesDetector::GamePiecesDetector(aos::EventLoop *event_loop)
-    : game_pieces_sender_(
-          event_loop->MakeSender<GamePieces>("/camera")) {
+    : game_pieces_sender_(event_loop->MakeSender<GamePieces>("/camera")) {
   event_loop->MakeWatcher("/camera", [this](const CameraImage &camera_image) {
     this->ProcessImage(camera_image);
   });
 }
 
+// TODO(FILIP): Actually do inference.
+
 void GamePiecesDetector::ProcessImage(const CameraImage &image) {
   // Param is not used for now.
   (void)image;
 
+  const int detection_count = 5;
+
   auto builder = game_pieces_sender_.MakeBuilder();
 
-  auto box_builder = builder.MakeBuilder<Box>();
-  box_builder.add_h(10);
-  box_builder.add_w(20);
-  box_builder.add_x(30);
-  box_builder.add_y(40);
-  auto box_offset = box_builder.Finish();
+  std::vector<flatbuffers::Offset<GamePiece>> game_pieces_offsets;
 
-  auto game_piece_builder = builder.MakeBuilder<GamePiece>();
-  game_piece_builder.add_piece_class(y2023::vision::Class::CONE_DOWN);
-  game_piece_builder.add_box(box_offset);
-  game_piece_builder.add_confidence(0.9);
-  auto game_piece = game_piece_builder.Finish();
+  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;
+
+    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);
+    auto box_offset = box_builder.Finish();
+
+    auto game_piece_builder = builder.MakeBuilder<GamePiece>();
+    game_piece_builder.add_piece_class(y2023::vision::Class::CONE_DOWN);
+    game_piece_builder.add_box(box_offset);
+    game_piece_builder.add_confidence(0.9);
+    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(std::vector<flatbuffers::Offset<GamePiece>>{game_piece});
+  auto game_pieces_vector = 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()));
 }
diff --git a/y2023/vision/game_pieces.fbs b/y2023/vision/game_pieces.fbs
index e981712..89f7505 100644
--- a/y2023/vision/game_pieces.fbs
+++ b/y2023/vision/game_pieces.fbs
@@ -2,14 +2,15 @@
 
 // Object class.
 enum Class : byte {
-    CONE_DOWN,
-    CONE_UP,
-    CUBE
+    NONE = 0,
+    CONE_UP = 1,
+    CUBE = 2,
+    CONE_DOWN = 3,
 }
 
 // Bounding box dimensions and position.
+// X and Y represent the top left of the bounding box.
 table Box {
-    //TODO(Filip): Are cords center of box or top left corner?
     x:uint (id: 0);
     y:uint (id: 1);
     w:uint (id: 2);
@@ -24,6 +25,7 @@
 
 table GamePieces {
     game_pieces:[GamePiece] (id: 0);
+    best_piece:uint (id: 1); // Index of the "best piece".
 }
 
-root_type GamePieces;
\ No newline at end of file
+root_type GamePieces;
diff --git a/y2023/vision/target_mapping.cc b/y2023/vision/target_mapping.cc
index e399470..9352bdd 100644
--- a/y2023/vision/target_mapping.cc
+++ b/y2023/vision/target_mapping.cc
@@ -20,8 +20,8 @@
 
 DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
               "Specify path for json with initial pose guesses.");
-DEFINE_string(config, "y2023/aos_config.json",
-              "Path to the config file to use.");
+DEFINE_string(config, "",
+              "If set, override the log's config file with this one.");
 DEFINE_string(constants_path, "y2023/constants/constants.json",
               "Path to the constant file");
 DEFINE_string(output_dir, "y2023/vision/maps",
@@ -76,6 +76,7 @@
     ceres::examples::Pose3d target_pose_camera =
         PoseUtils::Affine3dToPose3d(H_camera_target);
     double distance_from_camera = target_pose_camera.p.norm();
+    double distortion_factor = target_pose_fbs->distortion_factor();
 
     CHECK(map.has_monotonic_timestamp_ns())
         << "Need detection timestamps for mapping";
@@ -85,6 +86,7 @@
             .time = pi_distributed_time,
             .H_robot_target = H_robot_target,
             .distance_from_camera = distance_from_camera,
+            .distortion_factor = distortion_factor,
             .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
   }
 }
@@ -125,12 +127,15 @@
 
   std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
 
-  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+  std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
+      (FLAGS_config.empty()
+           ? std::nullopt
+           : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
 
   // open logfiles
-  aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles),
-                                &config.message());
+  aos::logger::LogReader reader(
+      aos::logger::SortParts(unsorted_logfiles),
+      config.has_value() ? &config->message() : nullptr);
   // Send new april tag poses. This allows us to take a log of images, then play
   // with the april detection code and see those changes take effect in mapping
   constexpr size_t kNumPis = 4;
diff --git a/y2023/y2023_imu.json b/y2023/y2023_imu.json
index 07c3b08..96134f8 100644
--- a/y2023/y2023_imu.json
+++ b/y2023/y2023_imu.json
@@ -312,7 +312,7 @@
       "name": "/localizer",
       "type": "frc971.controls.LocalizerOutput",
       "source_node": "imu",
-      "frequency": 210,
+      "frequency": 52,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
         "roborio"
@@ -334,7 +334,7 @@
       "type": "aos.message_bridge.RemoteMessage",
       "source_node": "imu",
       "logger": "NOT_LOGGED",
-      "frequency": 210,
+      "frequency": 52,
       "num_senders": 2,
       "max_size": 200
     },
diff --git a/y2023/y2023_logger.json b/y2023/y2023_logger.json
index 861372a..f4ac45e 100644
--- a/y2023/y2023_logger.json
+++ b/y2023/y2023_logger.json
@@ -21,26 +21,6 @@
       ]
     },
     {
-      "name": "/drivetrain",
-      "type": "frc971.control_loops.drivetrain.Position",
-      "source_node": "roborio",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "logger"
-      ],
-      "destination_nodes": [
-        {
-          "name": "logger",
-          "priority": 2,
-          "time_to_live": 500000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ]
-        }
-      ]
-    },
-    {
       "name": "/logger/camera",
       "type": "y2023.vision.GamePieces",
       "source_node": "logger",
@@ -73,44 +53,6 @@
       "max_size": 200
     },
     {
-      "name": "/roborio/aos/remote_timestamps/logger/drivetrain/frc971-control_loops-drivetrain-Position",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 400,
-      "num_senders": 2,
-      "max_size": 200
-    },
-    {
-      "name": "/drivetrain",
-      "type": "frc971.control_loops.drivetrain.Output",
-      "source_node": "roborio",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "logger"
-      ],
-      "destination_nodes": [
-        {
-          "name": "logger",
-          "priority": 2,
-          "time_to_live": 500000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ]
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/logger/drivetrain/frc971-control_loops-drivetrain-Output",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 400,
-      "num_senders": 2,
-      "max_size": 400
-    },
-    {
       "name": "/pi1/aos",
       "type": "aos.message_bridge.Timestamp",
       "source_node": "pi1",