Merge "Make it so that superstructure filters out NaN cone_position's"
diff --git a/frc971/can_logger/BUILD b/frc971/can_logger/BUILD
index a3b002a..a18a379 100644
--- a/frc971/can_logger/BUILD
+++ b/frc971/can_logger/BUILD
@@ -37,3 +37,36 @@
     gen_reflections = 1,
     visibility = ["//visibility:public"],
 )
+
+cc_binary(
+    name = "log_to_asc",
+    srcs = [
+        "log_to_asc.cc",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":asc_logger",
+        ":can_logging_fbs",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos/events/logging:log_reader",
+        "//aos/time",
+        "@com_github_google_glog//:glog",
+    ],
+)
+
+cc_library(
+    name = "asc_logger",
+    srcs = [
+        "asc_logger.cc",
+    ],
+    hdrs = [
+        "asc_logger.h",
+    ],
+    deps = [
+        ":can_logging_fbs",
+        "//aos/events:event_loop",
+        "//aos/scoped:scoped_fd",
+        "@com_github_google_glog//:glog",
+    ],
+)
diff --git a/frc971/can_logger/asc_logger.cc b/frc971/can_logger/asc_logger.cc
new file mode 100644
index 0000000..96b2e96
--- /dev/null
+++ b/frc971/can_logger/asc_logger.cc
@@ -0,0 +1,142 @@
+#include "frc971/can_logger/asc_logger.h"
+
+#include <linux/can.h>
+
+namespace frc971 {
+namespace can_logger {
+
+AscLogger::AscLogger(aos::EventLoop *event_loop, const std::string &filename)
+    : output_(filename), event_loop_(event_loop) {
+  CHECK(output_);
+  event_loop->MakeWatcher(
+      "/can", [this](const CanFrame &frame) { HandleFrame(frame); });
+}
+
+void AscLogger::HandleFrame(const CanFrame &frame) {
+  if (!first_frame_monotonic_) {
+    aos::monotonic_clock::time_point time(
+        std::chrono::nanoseconds(frame.monotonic_timestamp_ns()));
+
+    first_frame_monotonic_ = time;
+
+    WriteHeader(output_, event_loop_->realtime_now());
+  }
+
+  WriteFrame(output_, frame);
+}
+
+void AscLogger::WriteHeader(std::ostream &file,
+                            aos::realtime_clock::time_point start_time) {
+  file << "date " << start_time << "\n";
+  file << "base hex  timetamps absolute\n";
+  file << "no internal events logged\n";
+}
+
+namespace {
+
+static const unsigned char len2dlc[] = {
+    0,  1,  2,  3,  4,  5,  6,  7,  8, /* 0 - 8 */
+    9,  9,  9,  9,                     /* 9 - 12 */
+    10, 10, 10, 10,                    /* 13 - 16 */
+    11, 11, 11, 11,                    /* 17 - 20 */
+    12, 12, 12, 12,                    /* 21 - 24 */
+    13, 13, 13, 13, 13, 13, 13, 13,    /* 25 - 32 */
+    14, 14, 14, 14, 14, 14, 14, 14,    /* 33 - 40 */
+    14, 14, 14, 14, 14, 14, 14, 14,    /* 41 - 48 */
+    15, 15, 15, 15, 15, 15, 15, 15,    /* 49 - 56 */
+    15, 15, 15, 15, 15, 15, 15, 15};   /* 57 - 64 */
+
+/* map the sanitized data length to an appropriate data length code */
+unsigned char can_fd_len2dlc(unsigned char len) {
+  if (len > 64) return 0xF;
+
+  return len2dlc[len];
+}
+
+#define ASC_F_RTR 0x00000010
+#define ASC_F_FDF 0x00001000
+#define ASC_F_BRS 0x00002000
+#define ASC_F_ESI 0x00004000
+
+}  // namespace
+
+void AscLogger::WriteFrame(std::ostream &file, const CanFrame &frame) {
+  aos::monotonic_clock::time_point frame_timestamp(
+      std::chrono::nanoseconds(frame.monotonic_timestamp_ns()));
+
+  std::chrono::duration<double> time(frame_timestamp -
+                                     first_frame_monotonic_.value());
+
+  // TODO: maybe this should not be hardcoded
+  const int device_id = 1;
+
+  // EFF/SFF is set in the MSB
+  bool is_extended_frame_format = frame.can_id() & CAN_EFF_FLAG;
+
+  uint32_t id_mask = is_extended_frame_format ? CAN_EFF_MASK : CAN_SFF_MASK;
+  int id = frame.can_id() & id_mask;
+
+  // data length code
+  int dlc = can_fd_len2dlc(frame.data()->size());
+
+  const uint8_t flags = frame.flags();
+
+  uint32_t asc_flags = 0;
+
+  // Mark it as a CAN FD Frame
+  asc_flags = ASC_F_FDF;
+
+  // Pass through the bit rate switch flag
+  // indicates that it used a second bitrate for payload data
+  if (flags & CANFD_BRS) {
+    asc_flags |= ASC_F_BRS;
+  }
+
+  // ESI is the error state indicator of the transmitting node
+  if (flags & CANFD_ESI) {
+    asc_flags |= ASC_F_ESI;
+  }
+
+  file << std::fixed << time.count() << " ";
+
+  file << "CANFD ";
+
+  file << std::setfill(' ') << std::setw(3) << std::right << device_id << " ";
+
+  file << "Rx ";
+
+  std::stringstream formatted_id;
+  formatted_id << std::hex << std::uppercase << std::setfill('0') << id
+               << std::dec;
+  if (is_extended_frame_format) {
+    formatted_id << "x";
+  }
+
+  file << std::setfill(' ') << std::setw(11) << formatted_id.str();
+  file << "                                  ";
+
+  file << ((flags & CANFD_BRS) ? '1' : '0') << " ";
+  file << ((flags & CANFD_ESI) ? '1' : '0') << " ";
+
+  file << std::hex << std::nouppercase << dlc << std::dec << " ";
+
+  // actual data length
+  file << std::setfill(' ') << std::setw(2) << frame.data()->size();
+
+  file << std::hex << std::uppercase;
+  for (uint8_t byte : *frame.data()) {
+    file << " " << std::setfill('0') << std::setw(2) << static_cast<int>(byte);
+  }
+  file << std::dec;
+
+  // these are hardcoded in log2asc too, I don't know why
+  file << "   130000  130 ";
+  file << std::setfill(' ') << std::setw(8) << std::hex << asc_flags
+       << std::dec;
+  file << " 0 0 0 0 0";
+
+  file << "\n";
+}
+
+}  // namespace can_logger
+}  // namespace frc971
diff --git a/frc971/can_logger/asc_logger.h b/frc971/can_logger/asc_logger.h
new file mode 100644
index 0000000..213aa25
--- /dev/null
+++ b/frc971/can_logger/asc_logger.h
@@ -0,0 +1,38 @@
+#ifndef FRC971_CAN_LOGGER_ASC_LOGGER_H_
+#define FRC971_CAN_LOGGER_ASC_LOGGER_H_
+
+#include <iomanip>
+#include <iostream>
+
+#include "aos/events/event_loop.h"
+#include "frc971/can_logger/can_logging_generated.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+namespace frc971 {
+namespace can_logger {
+
+class AscLogger {
+ public:
+  AscLogger(aos::EventLoop *event_loop, const std::string &filename);
+
+ private:
+  void HandleFrame(const CanFrame &frame);
+
+  // This implementation attempts to duplicate the output of can-utils/log2asc
+  void WriteFrame(std::ostream &file, const CanFrame &frame);
+
+  static void WriteHeader(std::ostream &file,
+                          aos::realtime_clock::time_point start_time);
+
+  std::optional<aos::monotonic_clock::time_point> first_frame_monotonic_;
+
+  std::ofstream output_;
+
+  aos::EventLoop *event_loop_;
+};
+
+}  // namespace can_logger
+}  // namespace frc971
+
+#endif  // FRC971_CAN_LOGGER_ASC_LOGGER_H_
diff --git a/frc971/can_logger/can_logger.cc b/frc971/can_logger/can_logger.cc
index 6b4258a..ccd9824 100644
--- a/frc971/can_logger/can_logger.cc
+++ b/frc971/can_logger/can_logger.cc
@@ -72,6 +72,7 @@
 
   CanFrame::Builder can_frame_builder = builder.MakeBuilder<CanFrame>();
   can_frame_builder.add_can_id(frame.can_id);
+  can_frame_builder.add_flags(frame.flags);
   can_frame_builder.add_data(frame_data);
   can_frame_builder.add_monotonic_timestamp_ns(
       static_cast<std::chrono::nanoseconds>(
diff --git a/frc971/can_logger/can_logging.fbs b/frc971/can_logger/can_logging.fbs
index d6ec8b9..ba60241 100644
--- a/frc971/can_logger/can_logging.fbs
+++ b/frc971/can_logger/can_logging.fbs
@@ -8,6 +8,8 @@
   data:[ubyte] (id: 1);
   // The hardware timestamp of when the frame came in
   monotonic_timestamp_ns:uint64 (id: 2);
+  // Additional flags for CAN FD
+  flags: ubyte (id: 3);
 }
 
 root_type CanFrame;
diff --git a/frc971/can_logger/log_to_asc.cc b/frc971/can_logger/log_to_asc.cc
new file mode 100644
index 0000000..73ddd4e
--- /dev/null
+++ b/frc971/can_logger/log_to_asc.cc
@@ -0,0 +1,57 @@
+#include "aos/configuration.h"
+#include "aos/events/event_loop_generated.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/init.h"
+#include "frc971/can_logger/asc_logger.h"
+#include "frc971/can_logger/can_logging_generated.h"
+
+DEFINE_string(node, "", "Node to replay from the perspective of.");
+DEFINE_string(output_path, "/tmp/can_log.asc", "Log to output.");
+
+int main(int argc, char *argv[]) {
+  aos::InitGoogle(&argc, &argv);
+
+  const std::vector<aos::logger::LogFile> logfiles =
+      aos::logger::SortParts(aos::logger::FindLogs(argc, argv));
+  CHECK(!logfiles.empty());
+  const std::string logger_node = logfiles.at(0).logger_node;
+  bool all_logs_from_same_node = true;
+  for (const aos::logger::LogFile &log : logfiles) {
+    if (log.logger_node != logger_node) {
+      all_logs_from_same_node = false;
+      break;
+    }
+  }
+  std::string replay_node = FLAGS_node;
+  if (replay_node.empty() && all_logs_from_same_node) {
+    LOG(INFO) << "Guessing \"" << logger_node
+              << "\" as node given that --node was not specified.";
+    replay_node = logger_node;
+  }
+
+  std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config;
+
+  aos::logger::LogReader reader(
+      logfiles, config.has_value() ? &config.value().message() : nullptr);
+  aos::SimulatedEventLoopFactory factory(reader.configuration());
+  reader.RegisterWithoutStarting(&factory);
+
+  const aos::Node *node =
+      (replay_node.empty() ||
+       !aos::configuration::MultiNode(reader.configuration()))
+          ? nullptr
+          : aos::configuration::GetNode(reader.configuration(), replay_node);
+
+  std::unique_ptr<aos::EventLoop> can_event_loop;
+  CHECK(!FLAGS_output_path.empty());
+  std::unique_ptr<frc971::can_logger::AscLogger> relogger;
+
+  factory.GetNodeEventLoopFactory(node)->OnStartup([&relogger, &can_event_loop,
+                                                    &reader, node]() {
+    can_event_loop = reader.event_loop_factory()->MakeEventLoop("can", node);
+    relogger = std::make_unique<frc971::can_logger::AscLogger>(
+        can_event_loop.get(), FLAGS_output_path);
+  });
+  reader.event_loop_factory()->Run();
+  reader.Deregister();
+}
diff --git a/y2022_bot3/BUILD b/y2022_bot3/BUILD
index 8ccae67..e7146ce 100644
--- a/y2022_bot3/BUILD
+++ b/y2022_bot3/BUILD
@@ -8,23 +8,18 @@
     ],
     data = [
         ":aos_config",
-        "@ctre_phoenix_api_cpp_athena//:shared_libraries",
-        "@ctre_phoenix_cci_athena//:shared_libraries",
+        "@ctre_phoenixpro_api_cpp_athena//:shared_libraries",
+        "@ctre_phoenixpro_tools_athena//:shared_libraries",
     ],
     dirs = [
         "//y2022_bot3/actors:splines",
     ],
     start_binaries = [
         "//aos/events/logging:logger_main",
-        "//aos/network:web_proxy_main",
         ":joystick_reader",
         ":wpilib_interface",
-        "//aos/network:message_bridge_client",
-        "//aos/network:message_bridge_server",
-        "//y2022_bot3/actors:binaries",
         "//y2022_bot3/control_loops/drivetrain:drivetrain",
         "//y2022_bot3/control_loops/drivetrain:trajectory_generator",
-        "//y2022_bot3/control_loops/superstructure:superstructure",
     ],
     target_compatible_with = ["@platforms//os:linux"],
 )
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
index a97e0dd..8fd6d94 100644
--- a/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -27,7 +27,7 @@
   static constexpr double kImuYaw = 0.0;
   static DrivetrainConfig<double> kDrivetrainConfig{
       ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
-      ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
+      ::frc971::control_loops::drivetrain::LoopType::OPEN_LOOP,
       ::frc971::control_loops::drivetrain::GyroType::SPARTAN_GYRO,
       ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
 
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc
index fda7119..810e1f3 100644
--- a/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -19,6 +19,10 @@
           std::make_unique<::frc971::control_loops::drivetrain::DeadReckonEkf>(
               &event_loop,
               ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig());
+  std::unique_ptr<DrivetrainLoop> drivetrain = std::make_unique<DrivetrainLoop>(
+      y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig(), &event_loop,
+      localizer.get());
+
   event_loop.Run();
 
   return 0;
diff --git a/y2022_bot3/control_loops/python/drivetrain.py b/y2022_bot3/control_loops/python/drivetrain.py
index 8c5a2f8..638b3f3 100644
--- a/y2022_bot3/control_loops/python/drivetrain.py
+++ b/y2022_bot3/control_loops/python/drivetrain.py
@@ -14,7 +14,7 @@
 
 kDrivetrain = drivetrain.DrivetrainParams(
     J=6.0,
-    mass=58.0,
+    mass=28.0,
     # TODO(austin): Measure radius a bit better.
     robot_radius=0.39,
     wheel_radius=2.5 * 0.0254,
diff --git a/y2022_bot3/joystick_reader.cc b/y2022_bot3/joystick_reader.cc
index 00a28be..159123c 100644
--- a/y2022_bot3/joystick_reader.cc
+++ b/y2022_bot3/joystick_reader.cc
@@ -42,7 +42,7 @@
       : ::frc971::input::ActionJoystickInput(
             event_loop,
             ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig(),
-            ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
+            ::frc971::input::DrivetrainInputReader::InputType::kSteeringWheel, {}),
         superstructure_goal_sender_(
             event_loop->MakeSender<superstructure::Goal>("/superstructure")),
         superstructure_status_fetcher_(
diff --git a/y2022_bot3/y2022_bot3_roborio.json b/y2022_bot3/y2022_bot3_roborio.json
index 6485ed8..1a0712a 100644
--- a/y2022_bot3/y2022_bot3_roborio.json
+++ b/y2022_bot3/y2022_bot3_roborio.json
@@ -407,20 +407,6 @@
       ]
     },
     {
-      "name": "trajectory_generator",
-      "executable_name": "trajectory_generator",
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
-      "name": "superstructure",
-      "executable_name": "superstructure",
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
       "name": "joystick_reader",
       "executable_name": "joystick_reader",
       "nodes": [
@@ -433,45 +419,6 @@
       "nodes": [
         "roborio"
       ]
-    },
-    {
-      "name": "autonomous_action",
-      "executable_name": "autonomous_action",
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
-      "name": "web_proxy",
-      "executable_name": "web_proxy_main",
-      "args": ["--min_ice_port=5800", "--max_ice_port=5810"],
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
-      "name": "roborio_message_bridge_client",
-      "executable_name": "message_bridge_client.sh",
-      "args": ["--rt_priority=16"],
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
-      "name": "message_bridge_server",
-      "executable_name": "message_bridge_server",
-      "args": ["--rt_priority=16"],
-      "nodes": [
-        "roborio"
-      ]
-    },
-    {
-      "name": "logger",
-      "executable_name": "logger_main",
-      "args": ["--snappy_compress"],
-      "nodes": [
-        "roborio"
-      ]
     }
   ],
   "maps": [
diff --git a/y2023/autonomous/autonomous_actor.cc b/y2023/autonomous/autonomous_actor.cc
index c3ba65b..26197e3 100644
--- a/y2023/autonomous/autonomous_actor.cc
+++ b/y2023/autonomous/autonomous_actor.cc
@@ -328,14 +328,12 @@
 
   MidCubeScore();
 
-  if (!splines[3].WaitForSplineDistanceRemaining(0.05)) return;
+  if (!splines[3].WaitForSplineDistanceRemaining(0.07)) return;
   AOS_LOG(
       INFO, "Got back from second cube at %lf s\n",
       aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
 
   if (!WaitForArmGoal(0.05)) return;
-
-  if (!splines[3].WaitForSplineDistanceRemaining(0.05)) return;
   Spit();
 
   if (!splines[3].WaitForSplineDistanceRemaining(0.02)) return;
@@ -349,6 +347,8 @@
   const ProfileParametersT kTurn = MakeProfileParameters(3.0, 4.5);
   StartDrive(0.0, 0.0, kDrive, kTurn);
 
+  std::this_thread::sleep_for(chrono::milliseconds(100));
+
   {
     double side_scalar = (alliance_ == aos::Alliance::kRed) ? 1.0 : -1.0;
     StartDrive(6.33 - std::abs(X()), 0.0, kDrive, kTurn);
@@ -358,7 +358,7 @@
         INFO, "Done backing up %lf s\n",
         aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
 
-    const ProfileParametersT kInPlaceTurn = MakeProfileParameters(2.0, 4.5);
+    const ProfileParametersT kInPlaceTurn = MakeProfileParameters(2.5, 7.0);
     StartDrive(0.0, aos::math::NormalizeAngle(M_PI / 2.0 - Theta()), kDrive,
                kInPlaceTurn);
 
@@ -369,8 +369,13 @@
         INFO, "Roller off %lf s\n",
         aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
 
+    if (!WaitForTurnProfileNear(0.6)) return;
+    AOS_LOG(
+        INFO, "Balance arm %lf s\n",
+        aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
+
     Balance();
-    if (!WaitForTurnProfileNear(0.03)) return;
+    if (!WaitForTurnProfileNear(0.001)) return;
 
     AOS_LOG(
         INFO, "Done turning %lf s\n",
@@ -378,7 +383,7 @@
 
     const ProfileParametersT kDrive = MakeProfileParameters(1.4, 3.0);
     const ProfileParametersT kFinalTurn = MakeProfileParameters(3.0, 4.5);
-    const double kDriveDistance = 3.12;
+    const double kDriveDistance = 3.11;
     StartDrive(-kDriveDistance, 0.0, kDrive, kFinalTurn);
 
     const ProfileParametersT kFastTurn = MakeProfileParameters(5.0, 8.0);
@@ -461,7 +466,7 @@
 
 void AutonomousActor::Balance() {
   set_arm_goal_position(
-      control_loops::superstructure::arm::GroundPickupFrontConeUpIndex());
+      control_loops::superstructure::arm::ScoreFrontLowCubeIndex());
   set_wrist_goal(0.0);
   SendSuperstructureGoal();
 }
diff --git a/y2023/autonomous/splines/spline.1.json b/y2023/autonomous/splines/spline.1.json
index ada494a..22e739f 100644
--- a/y2023/autonomous/splines/spline.1.json
+++ b/y2023/autonomous/splines/spline.1.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [1.6230056318540846, 2.595606822913154, 3.185901688984583, 5.530672564287547, 5.959977921430404, 6.389283278573261], "spline_y": [0.4224994345862587, 0.509568426046465, 0.509568426046465, 0.28192333408803366, 0.29981105730231944, 0.29981105730231944], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [1.6230056318540846, 2.595606822913154, 3.5201381785640087, 5.572187770143549, 6.006069035460717, 6.435374392603574], "spline_y": [0.4224994345862587, 0.509568426046465, 0.8395233993107027, 0.4247693876940553, 0.4460951327369448, 0.4460951327369448], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2023/autonomous/splines/spline.2.json b/y2023/autonomous/splines/spline.2.json
index bbefb4e..4a24ffc 100644
--- a/y2023/autonomous/splines/spline.2.json
+++ b/y2023/autonomous/splines/spline.2.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [6.389283278573261, 5.998153290606758, 4.236658486151713, 2.789187490908938, 2.3614674084109164, 1.571420503593167], "spline_y": [0.29981105730231944, 0.29981105730231944, 0.6546640312799279, 0.8695373532912908, -0.061240797065554964, -0.6670628799510845], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.5}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [6.435374392603574, 6.0442444046370705, 4.96865071295785, 2.8506937641800936, 2.4156145282058796, 1.571420503593167], "spline_y": [0.4460951327369448, 0.4460951327369448, 0.3376418389076542, 1.2164153540583742, -0.13930255865735708, -0.6670628799510845], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.5}, {"constraint_type": "VOLTAGE", "value": 12.0}]}
\ No newline at end of file
diff --git a/y2023/autonomous/splines/spline.3.json b/y2023/autonomous/splines/spline.3.json
index d888718..bce0c4d 100644
--- a/y2023/autonomous/splines/spline.3.json
+++ b/y2023/autonomous/splines/spline.3.json
@@ -1 +1 @@
-{"spline_count": 1, "spline_x": [1.571420503593167, 3.182907251060901, 3.1860855438536575, 5.26674552341491, 4.916110025955861, 6.379956328994636], "spline_y": [-0.6670628799510845, 0.568653951467349, 0.5015288933650817, 0.5325195989567781, 0.24498490138963108, 0.24723266038664643], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.5}, {"constraint_type": "VOLTAGE", "value": 12.0}, {"constraint_type": "VELOCITY", "value": 1.5, "start_distance": 4.1, "end_distance": 10.0}]}
\ No newline at end of file
+{"spline_count": 1, "spline_x": [1.571420503593167, 3.533311283576554, 3.1860855438536575, 5.263533825984673, 4.912898328525625, 6.376744631564399], "spline_y": [-0.6670628799510845, 0.5594420208177215, 0.5015288933650817, 0.5641404302951452, 0.27660573272799804, 0.2788534917250134], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3.5}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2.5}, {"constraint_type": "VOLTAGE", "value": 12.0}, {"constraint_type": "VELOCITY", "value": 1.5, "start_distance": 4.1, "end_distance": 10.0}]}
\ No newline at end of file
diff --git a/y2023/constants.cc b/y2023/constants.cc
index 616b777..07b2ee6 100644
--- a/y2023/constants.cc
+++ b/y2023/constants.cc
@@ -100,7 +100,7 @@
       arm_distal->zeroing.one_revolution_distance =
           M_PI * 2.0 * constants::Values::kDistalEncoderRatio();
 
-      roll_joint->zeroing.measured_absolute_position = 0.62315534539819;
+      roll_joint->zeroing.measured_absolute_position = 0.619108755444215;
       roll_joint->potentiometer_offset =
           -(3.87038557084874 - 0.0241774522172967 + 0.0711345168020632 -
             0.866186131631967 - 0.0256788357596952 + 0.18101759154572017 -
@@ -111,7 +111,7 @@
           0.0317706563397807;
 
       wrist->subsystem_params.zeroing_constants.measured_absolute_position =
-          2.27068625283861;
+          2.29414865465015;
 
       break;
 
diff --git a/y2023/constants.h b/y2023/constants.h
index 595a694..f404472 100644
--- a/y2023/constants.h
+++ b/y2023/constants.h
@@ -194,8 +194,8 @@
   }
 
   static constexpr double kArmVMax() { return kArmGrannyMode() ? 4.0 : 9.5; }
-  static constexpr double kArmPathlessVMax() { return 4.5; }
-  static constexpr double kArmGotoPathVMax() { return 4.5; }
+  static constexpr double kArmPathlessVMax() { return 9.5; }
+  static constexpr double kArmGotoPathVMax() { return 9.5; }
 
   struct PotConstants {
     ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
diff --git a/y2023/control_loops/python/graph_paths.py b/y2023/control_loops/python/graph_paths.py
index 9aecb49..93134c7 100644
--- a/y2023/control_loops/python/graph_paths.py
+++ b/y2023/control_loops/python/graph_paths.py
@@ -386,7 +386,7 @@
         control_alpha_rolls=[(.95, -np.pi / 2.0)],
     ))
 
-points['Starting'] = np.array((np.pi, -0.125053863467887, 0.0))
+points['Starting'] = np.array((np.pi, -0.15, 0.0))
 
 points['ScoreFrontMidConeUpAuto'] = to_theta_with_circular_index_and_roll(
     0.58, 0.97, -np.pi / 2.0, circular_index=0)
@@ -398,7 +398,7 @@
         control1=np.array([2.99620794024176, 0.23620211875551145]),
         control2=np.array([2.728197531599509, 0.5677148040671784]),
         end=points['ScoreFrontMidConeUpAuto'],
-        control_alpha_rolls=[(0.20, 0.0), (.85, -np.pi / 2.0)],
+        control_alpha_rolls=[(.85, -np.pi / 2.0)],
         vmax=10.0,
         alpha_unitizer=np.matrix(
             f"{1.0 / 20.0} 0 0; 0 {1.0 / 25.0} 0; 0 0 {1.0 / 100.0}"),
diff --git a/y2023/control_loops/python/roll.py b/y2023/control_loops/python/roll.py
index 750b34f..25f8e9c 100644
--- a/y2023/control_loops/python/roll.py
+++ b/y2023/control_loops/python/roll.py
@@ -26,7 +26,7 @@
     # 598.006 in^2 lb
     J=0.175 * 3.0,
     q_pos=0.40,
-    q_vel=5.0,
+    q_vel=3.0,
     kalman_q_pos=0.12,
     kalman_q_vel=2.0,
     kalman_q_voltage=4.0,
diff --git a/y2023/control_loops/superstructure/arm/arm.cc b/y2023/control_loops/superstructure/arm/arm.cc
index fd3028c..7144e57 100644
--- a/y2023/control_loops/superstructure/arm/arm.cc
+++ b/y2023/control_loops/superstructure/arm/arm.cc
@@ -12,7 +12,7 @@
 namespace chrono = ::std::chrono;
 using ::aos::monotonic_clock;
 
-constexpr int kMaxBrownoutCount = 4;
+constexpr int kMaxBrownoutCount = 20;
 
 }  // namespace
 
@@ -248,7 +248,6 @@
 
   if (state_ == ArmState::RUNNING && unsafe_goal != nullptr) {
     if (current_node_ != filtered_goal) {
-      AOS_LOG(INFO, "Goal is different\n");
       if (filtered_goal >= search_graph_.num_vertexes()) {
         AOS_LOG(ERROR, "goal node out of range ESTOP\n");
         state_ = ArmState::ESTOP;
diff --git a/y2023/vision/target_mapping.cc b/y2023/vision/target_mapping.cc
index e9ef662..4da972a 100644
--- a/y2023/vision/target_mapping.cc
+++ b/y2023/vision/target_mapping.cc
@@ -81,7 +81,8 @@
                      Eigen::Affine3d extrinsics, std::string node_name,
                      frc971::vision::TargetMapper target_loc_mapper,
                      std::set<std::string> *drawn_nodes,
-                     VisualizeRobot *vis_robot, size_t *display_count) {
+                     VisualizeRobot *vis_robot, size_t *display_count,
+                     aos::distributed_clock::time_point *last_draw_time) {
   bool drew = false;
   std::stringstream label;
   label << node_name << " - ";
@@ -167,6 +168,7 @@
                                std::to_string(target_pose_fbs->id()),
                                kPiColors.at(node_name));
       drew = true;
+      *last_draw_time = pi_distributed_time;
     }
   }
   if (drew) {
@@ -177,6 +179,13 @@
                 kPiColors.at(node_name));
 
     drawn_nodes->emplace(node_name);
+  } else if (pi_distributed_time - *last_draw_time >
+                 std::chrono::milliseconds(30) &&
+             *display_count >= FLAGS_skip_to) {
+    // Clear the image if we haven't draw in a while
+    vis_robot->ClearImage();
+    cv::imshow("View", vis_robot->image_);
+    cv::waitKey(FLAGS_wait_key);
   }
 }
 
@@ -188,7 +197,7 @@
         *timestamped_target_detections,
     std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors,
     std::set<std::string> *drawn_nodes, VisualizeRobot *vis_robot,
-    size_t *display_count) {
+    size_t *display_count, aos::distributed_clock::time_point *last_draw_time) {
   static constexpr std::string_view kImageChannel = "/camera";
   // For the robots, we need to flip the image since the cameras are rolled by
   // 180 degrees
@@ -217,7 +226,7 @@
     std::string node_name = detection_event_loop->node()->name()->str();
     HandleAprilTags(map, pi_distributed_time, timestamped_target_detections,
                     extrinsics, node_name, target_loc_mapper, drawn_nodes,
-                    vis_robot, display_count);
+                    vis_robot, display_count, last_draw_time);
   });
 }
 
@@ -260,6 +269,8 @@
   VisualizeRobot vis_robot;
   std::set<std::string> drawn_nodes;
   size_t display_count = 0;
+  aos::distributed_clock::time_point last_draw_time =
+      aos::distributed_clock::min_time;
 
   const aos::Node *pi1 =
       aos::configuration::GetNode(reader.configuration(), "pi1");
@@ -269,7 +280,7 @@
       reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
   HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
                    &reader, &timestamped_target_detections, &detectors,
-                   &drawn_nodes, &vis_robot, &display_count);
+                   &drawn_nodes, &vis_robot, &display_count, &last_draw_time);
 
   const aos::Node *pi2 =
       aos::configuration::GetNode(reader.configuration(), "pi2");
@@ -279,7 +290,7 @@
       reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
   HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
                    &reader, &timestamped_target_detections, &detectors,
-                   &drawn_nodes, &vis_robot, &display_count);
+                   &drawn_nodes, &vis_robot, &display_count, &last_draw_time);
 
   const aos::Node *pi3 =
       aos::configuration::GetNode(reader.configuration(), "pi3");
@@ -289,7 +300,7 @@
       reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
   HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
                    &reader, &timestamped_target_detections, &detectors,
-                   &drawn_nodes, &vis_robot, &display_count);
+                   &drawn_nodes, &vis_robot, &display_count, &last_draw_time);
 
   const aos::Node *pi4 =
       aos::configuration::GetNode(reader.configuration(), "pi4");
@@ -299,7 +310,7 @@
       reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
   HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
                    &reader, &timestamped_target_detections, &detectors,
-                   &drawn_nodes, &vis_robot, &display_count);
+                   &drawn_nodes, &vis_robot, &display_count, &last_draw_time);
 
   std::unique_ptr<aos::EventLoop> mcap_event_loop;
   std::unique_ptr<aos::McapLogger> relogger;
diff --git a/y2023/y2023_imu.json b/y2023/y2023_imu.json
index 535d97f..5aae0a9 100644
--- a/y2023/y2023_imu.json
+++ b/y2023/y2023_imu.json
@@ -126,20 +126,10 @@
       "num_senders": 20,
       "max_size": 2048,
       "logger_nodes": [
-        "roborio",
         "logger"
       ],
       "destination_nodes": [
         {
-          "name": "roborio",
-          "priority": 5,
-          "time_to_live": 5000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "imu"
-          ]
-        },
-        {
           "name": "logger",
           "priority": 5,
           "time_to_live": 5000000,
@@ -172,20 +162,10 @@
       "num_senders": 2,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "roborio",
         "logger"
       ],
       "destination_nodes": [
         {
-          "name": "roborio",
-          "priority": 5,
-          "time_to_live": 5000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "imu"
-          ]
-        },
-        {
           "name": "logger",
           "priority": 5,
           "time_to_live": 5000000,
@@ -197,13 +177,6 @@
       ]
     },
     {
-      "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-starter-StarterRpc",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "imu",
-      "max_size": 208
-    },
-    {
       "name": "/imu/aos/remote_timestamps/logger/imu/aos/aos-starter-StarterRpc",
       "type": "aos.message_bridge.RemoteMessage",
       "frequency": 20,
@@ -366,35 +339,6 @@
       "max_size": 200
     },
     {
-      "name": "/roborio/aos",
-      "type": "aos.starter.Status",
-      "source_node": "roborio",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "imu"
-      ],
-      "destination_nodes": [
-        {
-          "name": "imu",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-Status",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 50,
-      "num_senders": 2,
-      "max_size": 200
-    },
-    {
       "name": "/localizer",
       "type": "frc971.IMUValuesBatch",
       "source_node": "imu",
diff --git a/y2023/y2023_logger.json b/y2023/y2023_logger.json
index 9b0ba55..df3a55b 100644
--- a/y2023/y2023_logger.json
+++ b/y2023/y2023_logger.json
@@ -37,7 +37,7 @@
           "priority": 2,
           "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
           "timestamp_logger_nodes": [
-            "roborio"
+            "logger"
           ],
           "time_to_live": 5000000
         }
@@ -64,7 +64,11 @@
         {
           "name": "logger",
           "priority": 1,
-          "time_to_live": 5000000
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi1"
+          ]
         }
       ]
     },
@@ -80,7 +84,11 @@
         {
           "name": "logger",
           "priority": 1,
-          "time_to_live": 5000000
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi2"
+          ]
         }
       ]
     },
@@ -96,6 +104,10 @@
         {
           "name": "logger",
           "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi3"
+          ],
           "time_to_live": 5000000
         }
       ]
@@ -112,6 +124,10 @@
         {
           "name": "logger",
           "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi4"
+          ],
           "time_to_live": 5000000
         }
       ]
@@ -157,64 +173,16 @@
       "name": "/logger/aos",
       "type": "aos.starter.Status",
       "source_node": "logger",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
       "frequency": 50,
       "num_senders": 20,
-      "max_size": 2000,
-      "logger_nodes": [
-        "roborio"
-      ],
-      "destination_nodes": [
-        {
-          "name": "roborio",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "logger"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-starter-Status",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "logger",
-      "logger": "NOT_LOGGED",
-      "frequency": 50,
-      "num_senders": 2,
-      "max_size": 200
+      "max_size": 2000
     },
     {
       "name": "/logger/aos",
       "type": "aos.starter.StarterRpc",
       "source_node": "logger",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "roborio"
-      ],
       "frequency": 10,
-      "num_senders": 2,
-      "destination_nodes": [
-        {
-          "name": "roborio",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "logger"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-starter-StarterRpc",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "logger",
-      "logger": "NOT_LOGGED",
-      "frequency": 20,
-      "num_senders": 2,
-      "max_size": 200
+      "num_senders": 2
     },
     {
       "name": "/logger/aos",
@@ -225,8 +193,12 @@
       "max_size": 400,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "roborio",
-        "imu"
+        "imu",
+        "pi1",
+        "pi2",
+        "pi3",
+        "pi4",
+        "roborio"
       ],
       "destination_nodes": [
         {
@@ -286,15 +258,6 @@
       ]
     },
     {
-      "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "logger",
-      "logger": "NOT_LOGGED",
-      "frequency": 20,
-      "num_senders": 2,
-      "max_size": 200
-    },
-    {
       "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-message_bridge-Timestamp",
       "type": "aos.message_bridge.RemoteMessage",
       "source_node": "logger",
@@ -340,6 +303,15 @@
       "max_size": 200
     },
     {
+      "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
       "name": "/logger/camera",
       "type": "frc971.vision.CameraImage",
       "source_node": "logger",
@@ -504,13 +476,13 @@
       "name": "pi3"
     },
     {
-      "name": "roborio"
-    },
-    {
       "name": "imu"
     },
     {
       "name": "pi4"
+    },
+    {
+      "name": "roborio"
     }
   ]
 }
diff --git a/y2023/y2023_pi_template.json b/y2023/y2023_pi_template.json
index 31f4045..46678f3 100644
--- a/y2023/y2023_pi_template.json
+++ b/y2023/y2023_pi_template.json
@@ -24,19 +24,17 @@
       "max_size": 2000,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "roborio",
         "logger"
       ],
       "destination_nodes": [
         {
-          "name": "roborio",
-          "priority": 5,
-          "time_to_live": 5000000
-        },
-        {
           "name": "logger",
           "priority": 5,
-          "time_to_live": 5000000
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi{{ NUM }}"
+          ]
         }
       ]
     },
@@ -48,23 +46,28 @@
       "num_senders": 2,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "roborio",
         "logger"
       ],
       "destination_nodes": [
         {
-          "name": "roborio",
-          "priority": 5,
-          "time_to_live": 5000000
-        },
-        {
           "name": "logger",
           "priority": 5,
-          "time_to_live": 5000000
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "pi{{ NUM }}"
+          ]
         }
       ]
     },
     {
+      "name": "/pi{{ NUM }}/aos/remote_timestamps/logger/pi{{ NUM }}/aos/aos-starter-StarterRpc",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "pi{{ NUM }}",
+      "max_size": 208
+    },
+    {
       "name": "/pi{{ NUM }}/aos",
       "type": "aos.message_bridge.ServerStatistics",
       "source_node": "pi{{ NUM }}",
@@ -93,39 +96,22 @@
       "num_senders": 2,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "roborio",
         "imu"
       ],
       "max_size": 200,
       "destination_nodes": [
         {
-          "name": "roborio",
-          "priority": 1,
-          "time_to_live": 5000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ]
-        },
-        {
           "name": "imu",
           "priority": 1,
           "time_to_live": 5000000,
           "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
           "timestamp_logger_nodes": [
-            "imu"
+            "pi{{ NUM }}"
           ]
         }
       ]
     },
     {
-      "name": "/pi{{ NUM }}/aos/remote_timestamps/roborio/pi{{ NUM }}/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "pi{{ NUM }}",
-      "max_size": 208
-    },
-    {
       "name": "/pi{{ NUM }}/aos/remote_timestamps/imu/pi{{ NUM }}/aos/aos-message_bridge-Timestamp",
       "type": "aos.message_bridge.RemoteMessage",
       "frequency": 20,
@@ -234,6 +220,10 @@
       "name": "/logger/aos",
       "type": "aos.starter.StarterRpc",
       "source_node": "logger",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "pi{{ NUM }}"
+      ],
       "destination_nodes": [
         {
           "name": "pi{{ NUM }}",
@@ -259,6 +249,10 @@
       "name": "/logger/aos",
       "type": "aos.starter.Status",
       "source_node": "logger",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "pi{{ NUM }}"
+      ],
       "destination_nodes": [
         {
           "name": "pi{{ NUM }}",
@@ -272,6 +266,22 @@
       ]
     },
     {
+      "name": "/pi{{ NUM }}/aos/remote_timestamps/logger/pi{{ NUM }}/aos/aos-starter-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 100,
+      "source_node": "pi{{ NUM }}",
+      "max_size": 208
+    },
+    {
+       "name": "/pi{{ NUM }}/aos/remote_timestamps/logger/pi{{ NUM }}/aos/aos-message_bridge-Timestamp",
+       "type": "aos.message_bridge.RemoteMessage",
+       "source_node": "pi{{ NUM }}",
+       "logger": "NOT_LOGGED",
+       "frequency": 15,
+       "num_senders": 2,
+       "max_size": 200
+    },
+    {
       "name": "/logger/aos/remote_timestamps/pi{{ NUM }}/logger/aos/aos-starter-Status",
       "type": "aos.message_bridge.RemoteMessage",
       "source_node": "logger",
@@ -281,56 +291,6 @@
       "max_size": 200
     },
     {
-      "name": "/roborio/aos",
-      "type": "aos.starter.StarterRpc",
-      "source_node": "roborio",
-      "destination_nodes": [
-        {
-          "name": "pi{{ NUM }}",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi{{ NUM }}/roborio/aos/aos-starter-StarterRpc",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 20,
-      "num_senders": 2,
-      "max_size": 200
-    },
-    {
-      "name": "/roborio/aos",
-      "type": "aos.starter.Status",
-      "source_node": "roborio",
-      "destination_nodes": [
-        {
-          "name": "pi{{ NUM }}",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi{{ NUM }}/roborio/aos/aos-starter-Status",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 50,
-      "num_senders": 2,
-      "max_size": 200
-    },
-    {
       "name": "/pi{{ NUM }}/constants",
       "type": "y2023.Constants",
       "source_node": "pi{{ NUM }}",
@@ -492,9 +452,6 @@
     },
     {
       "name": "imu"
-    },
-    {
-      "name": "roborio"
     }
   ]
 }
diff --git a/y2023/y2023_roborio.json b/y2023/y2023_roborio.json
index 452a570..2888690 100644
--- a/y2023/y2023_roborio.json
+++ b/y2023/y2023_roborio.json
@@ -7,18 +7,13 @@
       "frequency": 100,
       "logger": "LOCAL_AND_REMOTE_LOGGER",
       "logger_nodes": [
-        "imu",
-        "logger"
+        "imu"
       ],
       "destination_nodes": [
         {
           "name": "imu",
           "priority": 5,
-          "time_to_live": 50000000,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ]
+          "time_to_live": 50000000
         }
       ]
     },
@@ -59,31 +54,7 @@
       "source_node": "roborio",
       "frequency": 50,
       "num_senders": 20,
-      "max_size": 2000,
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "logger"
-      ],
-      "destination_nodes": [
-        {
-          "name": "logger",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-starter-Status",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 50,
-      "num_senders": 2,
-      "max_size": 200
+      "max_size": 2000
     },
     {
       "name": "/roborio/aos",
@@ -91,31 +62,7 @@
       "source_node": "roborio",
       "frequency": 10,
       "max_size": 400,
-      "num_senders": 2,
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "logger"
-      ],
-      "destination_nodes": [
-        {
-          "name": "logger",
-          "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        }
-      ]
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-starter-StarterRpc",
-      "type": "aos.message_bridge.RemoteMessage",
-      "source_node": "roborio",
-      "logger": "NOT_LOGGED",
-      "frequency": 20,
-      "num_senders": 2,
-      "max_size": 200
+      "num_senders": 2
     },
     {
       "name": "/roborio/aos",
@@ -140,38 +87,6 @@
       "num_senders": 2
     },
     {
-      "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 300,
-      "source_node": "roborio"
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi1/roborio/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "roborio",
-      "max_size": 208
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi2/roborio/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "roborio",
-      "max_size": 208
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi3/roborio/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "roborio"
-    },
-    {
-      "name": "/roborio/aos/remote_timestamps/pi4/roborio/aos/aos-message_bridge-Timestamp",
-      "type": "aos.message_bridge.RemoteMessage",
-      "frequency": 20,
-      "source_node": "roborio"
-    },
-    {
       "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-message_bridge-Timestamp",
       "type": "aos.message_bridge.RemoteMessage",
       "frequency": 20,
@@ -179,6 +94,12 @@
       "max_size": 208
     },
     {
+      "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 300,
+      "source_node": "roborio"
+    },
+    {
       "name": "/roborio/aos",
       "type": "aos.message_bridge.Timestamp",
       "source_node": "roborio",
@@ -191,42 +112,6 @@
       ],
       "destination_nodes": [
         {
-          "name": "pi1",
-          "priority": 1,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        },
-        {
-          "name": "pi2",
-          "priority": 1,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        },
-        {
-          "name": "pi3",
-          "priority": 1,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        },
-        {
-          "name": "pi4",
-          "priority": 1,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "roborio"
-          ],
-          "time_to_live": 5000000
-        },
-        {
           "name": "imu",
           "priority": 1,
           "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -344,10 +229,6 @@
         {
           "name": "imu",
           "priority": 5,
-          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
-          "timestamp_logger_nodes": [
-            "imu"
-          ],
           "time_to_live": 5000000
         }
       ]
@@ -385,7 +266,7 @@
           "priority": 5,
           "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
           "timestamp_logger_nodes": [
-            "imu"
+            "roborio"
           ],
           "time_to_live": 0
         }
@@ -578,6 +459,7 @@
     {
       "name": "can_logger",
       "executable_name": "can_logger",
+      "autostart": false,
       "nodes": [
         "roborio"
       ]