Merge "Update Cypress and Chromium"
diff --git a/scouting/db/db.go b/scouting/db/db.go
index 5d7a56c..016ca95 100644
--- a/scouting/db/db.go
+++ b/scouting/db/db.go
@@ -86,6 +86,7 @@
 	NotesDropped                                 int32
 	Penalties                                    int32
 	AvgCycle                                     int64
+	RobotDied                                    bool
 	Park, OnStage, Harmony, TrapNote, Spotlight  bool
 
 	// The username of the person who collected these statistics.
diff --git a/scouting/db/db_test.go b/scouting/db/db_test.go
index 369ea58..882dfbc 100644
--- a/scouting/db/db_test.go
+++ b/scouting/db/db_test.go
@@ -149,7 +149,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "emma",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "942",
@@ -157,7 +157,7 @@
 			SpeakerAuto: 2, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "harry",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "harry",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "432",
@@ -165,7 +165,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 2, Amp: 1, SpeakerAmplified: 3, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "henry",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "henry",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "52A",
@@ -173,7 +173,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 0, Amp: 1, SpeakerAmplified: 2, AmpAmplified: 3,
 			NotesDropped: 2, Penalties: 0, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "jordan",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "jordan",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "745",
@@ -181,7 +181,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 5, Amp: 0, SpeakerAmplified: 2, AmpAmplified: 1,
 			NotesDropped: 1, Penalties: 1, TrapNote: true, Spotlight: true, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "taylor",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "taylor",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "934",
@@ -189,7 +189,7 @@
 			SpeakerAuto: 1, AmpAuto: 3, NotesDroppedAuto: 0, MobilityAuto: true,
 			Speaker: 0, Amp: 3, SpeakerAmplified: 2, AmpAmplified: 2,
 			NotesDropped: 0, Penalties: 3, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: false, Harmony: true, CollectedBy: "katie",
+			Park: false, OnStage: false, Harmony: true, RobotDied: false, CollectedBy: "katie",
 		},
 	}
 
@@ -236,7 +236,7 @@
 		SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 		Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 		NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-		Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+		Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "emma",
 	}
 
 	// Attempt to insert the non-pre-scouted data and make sure it fails.
@@ -265,7 +265,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "emma",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "emma",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "978",
@@ -273,7 +273,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 1, Amp: 2, SpeakerAmplified: 0, AmpAmplified: 2,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "emma",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "328A",
@@ -281,7 +281,7 @@
 			SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
 			Speaker: 0, Amp: 1, SpeakerAmplified: 1, AmpAmplified: 5,
 			NotesDropped: 1, Penalties: 0, TrapNote: false, Spotlight: true, AvgCycle: 0,
-			Park: false, OnStage: false, Harmony: true, CollectedBy: "emma",
+			Park: false, OnStage: false, Harmony: true, RobotDied: true, CollectedBy: "emma",
 		},
 	}
 
@@ -700,7 +700,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 1, Amp: 3, SpeakerAmplified: 1, AmpAmplified: 3,
 			NotesDropped: 0, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "bailey",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "bailey",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "645",
@@ -708,7 +708,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 1, Amp: 2, SpeakerAmplified: 0, AmpAmplified: 1,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "kate",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "kate",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "323",
@@ -716,7 +716,7 @@
 			SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
 			Speaker: 0, Amp: 0, SpeakerAmplified: 2, AmpAmplified: 1,
 			NotesDropped: 1, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "tyler",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "tyler",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "542",
@@ -724,7 +724,7 @@
 			SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 1, Amp: 2, SpeakerAmplified: 2, AmpAmplified: 1,
 			NotesDropped: 1, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: false, Harmony: true, CollectedBy: "max",
+			Park: false, OnStage: false, Harmony: true, RobotDied: false, CollectedBy: "max",
 		},
 	}
 
@@ -735,7 +735,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 1, Amp: 3, SpeakerAmplified: 1, AmpAmplified: 3,
 			NotesDropped: 0, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "bailey",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "bailey",
 		},
 	}
 
@@ -1154,7 +1154,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "emma",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "942",
@@ -1162,7 +1162,7 @@
 			SpeakerAuto: 2, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 2, TrapNote: true, Spotlight: false, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "harry",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "harry",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "432",
@@ -1170,7 +1170,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
 			Speaker: 2, Amp: 1, SpeakerAmplified: 3, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "henry",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "henry",
 		},
 		Stats2024{
 			PreScouting: false, TeamNumber: "52A",
@@ -1178,7 +1178,7 @@
 			SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 0, Amp: 1, SpeakerAmplified: 2, AmpAmplified: 3,
 			NotesDropped: 2, Penalties: 0, TrapNote: true, Spotlight: true, AvgCycle: 0,
-			Park: true, OnStage: false, Harmony: false, CollectedBy: "jordan",
+			Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "jordan",
 		},
 	}
 
diff --git a/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs b/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs
index c36174d..f450d38 100644
--- a/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs
+++ b/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs
@@ -26,6 +26,7 @@
   on_stage: bool (id:16);
   harmony: bool (id:17);
   spotlight: bool (id:22);
+  robot_died: bool (id:23);
 
   pre_scouting:bool (id:20);
   collected_by:string (id:21);
diff --git a/scouting/webserver/requests/messages/submit_2024_actions.fbs b/scouting/webserver/requests/messages/submit_2024_actions.fbs
index e85563f..9462fbe 100644
--- a/scouting/webserver/requests/messages/submit_2024_actions.fbs
+++ b/scouting/webserver/requests/messages/submit_2024_actions.fbs
@@ -9,6 +9,7 @@
     kAMP_AMPLIFIED,
     kSPEAKER,
     kSPEAKER_AMPLIFIED,
+    kDROPPED,
 }
 
 table MobilityAction {
diff --git a/scouting/webserver/requests/requests.go b/scouting/webserver/requests/requests.go
index 76d632d..7d6e98e 100644
--- a/scouting/webserver/requests/requests.go
+++ b/scouting/webserver/requests/requests.go
@@ -452,7 +452,7 @@
 		PreScouting: submit2024Actions.PreScouting(), TeamNumber: string(submit2024Actions.TeamNumber()), MatchNumber: submit2024Actions.MatchNumber(), SetNumber: submit2024Actions.SetNumber(), CompLevel: string(submit2024Actions.CompLevel()),
 		StartingQuadrant: 0, SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 		Speaker: 0, Amp: 0, SpeakerAmplified: 0, AmpAmplified: 0, NotesDropped: 0, Penalties: 0,
-		TrapNote: false, Spotlight: false, AvgCycle: 0, Park: false, OnStage: false, Harmony: false, CollectedBy: "",
+		TrapNote: false, Spotlight: false, AvgCycle: 0, Park: false, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "",
 	}
 	// Loop over all actions.
 	for i := 0; i < submit2024Actions.ActionsListLength(); i++ {
@@ -481,19 +481,15 @@
 			penaltyAction.Init(actionTable.Bytes, actionTable.Pos)
 			stat.Penalties += penaltyAction.Penalties()
 
+		} else if action_type == submit_2024_actions.ActionTypeRobotDeathAction {
+			var robotDeathAction submit_2024_actions.RobotDeathAction
+			robotDeathAction.Init(actionTable.Bytes, actionTable.Pos)
+			stat.RobotDied = true
+
 		} else if action_type == submit_2024_actions.ActionTypePickupNoteAction {
 			var pick_up_action submit_2024_actions.PickupNoteAction
 			pick_up_action.Init(actionTable.Bytes, actionTable.Pos)
-			if picked_up == true {
-				auto := pick_up_action.Auto()
-				if auto == false {
-					stat.NotesDropped += 1
-				} else {
-					stat.NotesDroppedAuto += 1
-				}
-			} else {
-				picked_up = true
-			}
+			picked_up = true
 		} else if action_type == submit_2024_actions.ActionTypePlaceNoteAction {
 			var place_action submit_2024_actions.PlaceNoteAction
 			place_action.Init(actionTable.Bytes, actionTable.Pos)
@@ -514,6 +510,10 @@
 				stat.SpeakerAuto += 1
 			} else if score_type == submit_2024_actions.ScoreTypekSPEAKER_AMPLIFIED && !auto {
 				stat.SpeakerAmplified += 1
+			} else if score_type == submit_2024_actions.ScoreTypekDROPPED && auto {
+				stat.NotesDroppedAuto += 1
+			} else if score_type == submit_2024_actions.ScoreTypekDROPPED && !auto {
+				stat.NotesDropped += 1
 			} else {
 				return db.Stats2024{}, errors.New(fmt.Sprintf("Got unknown ObjectType/ScoreLevel/Auto combination"))
 			}
@@ -595,6 +595,7 @@
 			Park:             stat.Park,
 			OnStage:          stat.OnStage,
 			Harmony:          stat.Harmony,
+			RobotDied:        stat.RobotDied,
 			CollectedBy:      stat.CollectedBy,
 		})
 	}
diff --git a/scouting/webserver/requests/requests_test.go b/scouting/webserver/requests/requests_test.go
index ebe73f3..26fad0f 100644
--- a/scouting/webserver/requests/requests_test.go
+++ b/scouting/webserver/requests/requests_test.go
@@ -137,8 +137,8 @@
 				MatchNumber: 1, SetNumber: 1, CompLevel: "qm", StartingQuadrant: 3,
 				SpeakerAuto: 2, AmpAuto: 4, NotesDroppedAuto: 1, MobilityAuto: true,
 				Speaker: 0, Amp: 1, SpeakerAmplified: 2, AmpAmplified: 1,
-				NotesDropped: 0, Penalties: 01, TrapNote: true, Spotlight: false, AvgCycle: 233,
-				Park: false, OnStage: true, Harmony: false, CollectedBy: "alex",
+				NotesDropped: 0, Penalties: 1, TrapNote: true, Spotlight: false, AvgCycle: 233,
+				Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "alex",
 			},
 			{
 				PreScouting: false, TeamNumber: "973",
@@ -146,7 +146,7 @@
 				SpeakerAuto: 0, AmpAuto: 2, NotesDroppedAuto: 0, MobilityAuto: false,
 				Speaker: 0, Amp: 4, SpeakerAmplified: 3, AmpAmplified: 1,
 				NotesDropped: 0, Penalties: 1, TrapNote: true, Spotlight: false, AvgCycle: 120,
-				Park: true, OnStage: false, Harmony: false, CollectedBy: "bob",
+				Park: true, OnStage: false, Harmony: false, RobotDied: true, CollectedBy: "bob",
 			},
 		},
 	}
@@ -215,7 +215,7 @@
 				SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: true,
 				Speaker: 4, Amp: 2, SpeakerAmplified: 1, AmpAmplified: 0,
 				NotesDropped: 2, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-				Park: true, OnStage: false, Harmony: false, CollectedBy: "alex",
+				Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "alex",
 			},
 			{
 				PreScouting: false, TeamNumber: "982",
@@ -223,7 +223,7 @@
 				SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 				Speaker: 0, Amp: 2, SpeakerAmplified: 3, AmpAmplified: 2,
 				NotesDropped: 1, Penalties: 0, TrapNote: false, Spotlight: true, AvgCycle: 0,
-				Park: false, OnStage: true, Harmony: false, CollectedBy: "george",
+				Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "george",
 			},
 		},
 	}
@@ -248,7 +248,7 @@
 				SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: true,
 				Speaker: 4, Amp: 2, SpeakerAmplified: 1, AmpAmplified: 0,
 				NotesDropped: 2, Penalties: 2, TrapNote: true, Spotlight: true, AvgCycle: 0,
-				Park: true, OnStage: false, Harmony: false, CollectedBy: "alex",
+				Park: true, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "alex",
 			},
 			{
 				PreScouting: false, TeamNumber: "982",
@@ -256,7 +256,7 @@
 				SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 				Speaker: 0, Amp: 2, SpeakerAmplified: 3, AmpAmplified: 2,
 				NotesDropped: 1, Penalties: 0, TrapNote: false, Spotlight: true, AvgCycle: 0,
-				Park: false, OnStage: true, Harmony: false, CollectedBy: "george",
+				Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "george",
 			},
 		},
 	}
@@ -441,6 +441,43 @@
 						Auto: false,
 					},
 				},
+				Timestamp: 3200,
+			},
+			{
+				ActionTaken: &submit_2024_actions.ActionTypeT{
+					Type: submit_2024_actions.ActionTypePlaceNoteAction,
+					Value: &submit_2024_actions.PlaceNoteActionT{
+						ScoreType: submit_2024_actions.ScoreTypekDROPPED,
+						Auto:      false,
+					},
+				},
+				Timestamp: 3300,
+			},
+			{
+				ActionTaken: &submit_2024_actions.ActionTypeT{
+					Type: submit_2024_actions.ActionTypeRobotDeathAction,
+					Value: &submit_2024_actions.RobotDeathActionT{
+						RobotDead: true,
+					},
+				},
+				Timestamp: 3400,
+			},
+			{
+				ActionTaken: &submit_2024_actions.ActionTypeT{
+					Type: submit_2024_actions.ActionTypeRobotDeathAction,
+					Value: &submit_2024_actions.RobotDeathActionT{
+						RobotDead: false,
+					},
+				},
+				Timestamp: 3450,
+			},
+			{
+				ActionTaken: &submit_2024_actions.ActionTypeT{
+					Type: submit_2024_actions.ActionTypePickupNoteAction,
+					Value: &submit_2024_actions.PickupNoteActionT{
+						Auto: false,
+					},
+				},
 				Timestamp: 3500,
 			},
 			{
@@ -478,10 +515,10 @@
 	expected := db.Stats2024{
 		PreScouting: false, TeamNumber: "4244",
 		MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
-		SpeakerAuto: 0, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
+		SpeakerAuto: 0, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: true,
 		Speaker: 0, Amp: 0, SpeakerAmplified: 1, AmpAmplified: 1,
-		NotesDropped: 0, Penalties: 5, TrapNote: false, Spotlight: false, AvgCycle: 950,
-		Park: false, OnStage: false, Harmony: true, CollectedBy: "",
+		NotesDropped: 1, Penalties: 5, TrapNote: false, Spotlight: false, AvgCycle: 633,
+		Park: false, OnStage: false, Harmony: true, RobotDied: true, CollectedBy: "",
 	}
 
 	if expected != response {
@@ -1202,7 +1239,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 1, Amp: 0, SpeakerAmplified: 0, AmpAmplified: 0,
 			NotesDropped: 0, Penalties: 0, TrapNote: false, Spotlight: false, AvgCycle: 0,
-			Park: false, OnStage: false, Harmony: false, CollectedBy: "debug_cli",
+			Park: false, OnStage: false, Harmony: false, RobotDied: false, CollectedBy: "debug_cli",
 		},
 	}
 
@@ -1448,7 +1485,7 @@
 				SpeakerAuto: 0, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
 				Speaker: 0, Amp: 1, SpeakerAmplified: 1, AmpAmplified: 1,
 				NotesDropped: 0, Penalties: 1, TrapNote: true, Spotlight: false, AvgCycle: 233,
-				Park: false, OnStage: false, Harmony: true, CollectedBy: "alek",
+				Park: false, OnStage: false, Harmony: true, RobotDied: false, CollectedBy: "alek",
 			},
 			{
 				PreScouting: false, TeamNumber: "244",
@@ -1456,7 +1493,7 @@
 				SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 				Speaker: 0, Amp: 0, SpeakerAmplified: 3, AmpAmplified: 1,
 				NotesDropped: 0, Penalties: 1, TrapNote: false, Spotlight: false, AvgCycle: 120,
-				Park: false, OnStage: true, Harmony: false, CollectedBy: "kacey",
+				Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "kacey",
 			},
 		},
 		actions: []db.Action{
@@ -1520,7 +1557,7 @@
 			SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
 			Speaker: 0, Amp: 0, SpeakerAmplified: 3, AmpAmplified: 1,
 			NotesDropped: 0, Penalties: 1, TrapNote: false, Spotlight: false, AvgCycle: 120,
-			Park: false, OnStage: true, Harmony: false, CollectedBy: "kacey",
+			Park: false, OnStage: true, Harmony: false, RobotDied: false, CollectedBy: "kacey",
 		},
 	}
 
diff --git a/scouting/www/entry/entry.component.css b/scouting/www/entry/entry.component.css
index 9c50ee0..cd208b9 100644
--- a/scouting/www/entry/entry.component.css
+++ b/scouting/www/entry/entry.component.css
@@ -20,5 +20,11 @@
 }
 
 #EndGame > div > label {
-  padding: 0;
+  padding: 0px;
+}
+
+.button_row {
+  display: flex;
+  width: 90vw;
+  justify-content: space-between;
 }
diff --git a/scouting/www/entry/entry.component.ts b/scouting/www/entry/entry.component.ts
index b5bc51e..6da8be8 100644
--- a/scouting/www/entry/entry.component.ts
+++ b/scouting/www/entry/entry.component.ts
@@ -75,7 +75,7 @@
   | {
       type: 'robotDeathAction';
       timestamp?: number;
-      robotOn: boolean;
+      robotDead: boolean;
     }
   | {
       type: 'penaltyAction';
@@ -363,7 +363,7 @@
 
         case 'robotDeathAction':
           const robotDeathActionOffset =
-            RobotDeathAction.createRobotDeathAction(builder, action.robotOn);
+            RobotDeathAction.createRobotDeathAction(builder, action.robotDead);
           actionOffset = Action.createAction(
             builder,
             BigInt(action.timestamp || 0),
diff --git a/scouting/www/entry/entry.ng.html b/scouting/www/entry/entry.ng.html
index ea44ad3..22d2d27 100644
--- a/scouting/www/entry/entry.ng.html
+++ b/scouting/www/entry/entry.ng.html
@@ -123,7 +123,7 @@
       <button class="btn btn-secondary" (click)="undoLastAction()">UNDO</button>
       <button
         class="btn btn-danger"
-        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotOn: false});"
+        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotDead: true});"
       >
         DEAD
       </button>
@@ -183,15 +183,21 @@
       selection and keep all buttons visible without scrolling on most devices.
     -->
     <div
-      [ngClass]="{'d-grid': true, 'gap-3': autoPhase === true, 'gap-5': autoPhase === false}"
+      [ngClass]="{'d-grid': true, 'gap-4': autoPhase === true, 'gap-3': autoPhase === false}"
     >
       <button class="btn btn-secondary" (click)="undoLastAction()">UNDO</button>
       <button
         class="btn btn-danger"
-        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotOn: false});"
+        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotDead: true});"
       >
         DEAD
       </button>
+      <button
+        class="btn btn-info"
+        (click)="changeSectionTo('Pickup'); addAction({type: 'placeNoteAction', scoreType: ScoreType.kDROPPED});"
+      >
+        Dropped
+      </button>
       <div *ngIf="!autoPhase" class="d-grid gap-1" style="padding: 0">
         <div
           style="
@@ -298,40 +304,54 @@
       <button class="btn btn-secondary" (click)="undoLastAction()">UNDO</button>
       <button
         class="btn btn-danger"
-        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotOn: false});"
+        (click)="changeSectionTo('Dead'); addAction({type: 'robotDeathAction', robotDead: true});"
       >
         DEAD
       </button>
-      <label>
-        <input
-          #park
-          type="radio"
-          id="option1"
-          name="endgameaction"
-          value="park"
-        />
-        Park
-      </label>
-      <label>
-        <input
-          #onStage
-          type="radio"
-          id="option2"
-          name="endgameaction"
-          value="onStage"
-        />
-        On Stage
-      </label>
-      <label>
-        <input
-          #harmony
-          type="radio"
-          id="option3"
-          name="endgameaction"
-          value="harmony"
-        />
-        Harmony
-      </label>
+      <div class="button_row">
+        <label>
+          <input
+            #park
+            type="radio"
+            id="option1"
+            name="endgameaction"
+            value="park"
+          />
+          Park
+        </label>
+        <label>
+          <input
+            #onStage
+            type="radio"
+            id="option2"
+            name="endgameaction"
+            value="onStage"
+          />
+          On Stage
+        </label>
+      </div>
+      <div class="button_row">
+        <label>
+          <input
+            #harmony
+            type="radio"
+            id="option3"
+            name="endgameaction"
+            value="harmony"
+          />
+          Harmony
+        </label>
+        <label>
+          <input
+            #na
+            type="radio"
+            id="option2"
+            name="endgameaction"
+            value="na"
+          />
+          N/A
+        </label>
+      </div>
       <label>
         <input
           #trapNote
@@ -352,6 +372,7 @@
         />
         Spotlight
       </label>
+
       <div style="display: flex">
         <h5>Penalties :</h5>
         <button
@@ -381,13 +402,39 @@
   </div>
   <div *ngSwitchCase="'Dead'" id="Dead" class="container-fluid">
     <h2>Robot is dead</h2>
-    <div class="d-grid gap-2">
+    <div class="d-grid gap-3">
+      <button class="btn btn-secondary" (click)="undoLastAction()">UNDO</button>
+      <div style="display: flex">
+        <h5>Penalties :</h5>
+        <button
+          class="btn-light"
+          style="width: 40px; margin-right: 15px"
+          (click)="removePenalty()"
+        >
+          -
+        </button>
+        <p>{{this.penalties}}</p>
+        <button
+          class="btn-light"
+          style="width: 40px; margin-left: 15px"
+          (click)="addPenalty()"
+        >
+          +
+        </button>
+      </div>
       <button
         class="btn btn-success"
-        (click)="changeSectionTo('Pickup'); addAction({type: 'robotDeathAction', robotOn: true}); "
+        (click)="changeSectionTo('Pickup'); addAction({type: 'robotDeathAction', robotDead: false}); "
       >
         Revive
       </button>
+      <button
+        *ngIf="!autoPhase"
+        class="btn btn-info"
+        (click)="changeSectionTo('Review and Submit');  addPenalties(); addAction({type: 'endMatchAction', stageType: (park.checked ? StageType.kPARK : onStage.checked ? StageType.kON_STAGE : harmony.checked ? StageType.kHARMONY : StageType.kMISSING), trapNote: trapNote.checked, spotlight: spotlight.checked});"
+      >
+        End Match
+      </button>
     </div>
   </div>
   <div *ngSwitchCase="'Review and Submit'" id="Review" class="container-fluid">
@@ -414,7 +461,7 @@
               spotlight: {{action.spotlight}}
             </span>
             <span *ngSwitchCase="'robotDeathAction'">
-              Robot on: {{action.robotOn}}
+              Robot dead: {{action.robotDead}}
             </span>
             <span *ngSwitchCase="'mobilityAction'">
               Mobility: {{action.mobility}}
diff --git a/y2024/constants/7971.json b/y2024/constants/7971.json
index d46daba..be70754 100644
--- a/y2024/constants/7971.json
+++ b/y2024/constants/7971.json
@@ -8,16 +8,16 @@
 {
   "cameras": [
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-2-0_cam-24-01_2024-02-07_20-11-35.566609408.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_imu-7971-0_cam-24-01_2024-03-02_19-44-12.098903651.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-02-07_20-11-32.368359264.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-03-02_20-09-18.022901293.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-2-1_cam-24-03_2024-02-07_20-40-34.928600992.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-c-1_cam-24-03_2024-03-02_20-09-18.016217514.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-02-07_20-45-22.787382400.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-03-02_20-09-18.016860291.json' %}
     }
   ],
   "robot": {
diff --git a/y2024/constants/calib_files/calibration_orin-7971-2-0_cam-24-01_2024-02-07_20-11-35.566609408.json b/y2024/constants/calib_files/calibration_imu-7971-0_cam-24-01_2024-03-02_19-44-12.098903651.json
similarity index 63%
rename from y2024/constants/calib_files/calibration_orin-7971-2-0_cam-24-01_2024-02-07_20-11-35.566609408.json
rename to y2024/constants/calib_files/calibration_imu-7971-0_cam-24-01_2024-03-02_19-44-12.098903651.json
index c68e857..13301a0 100755
--- a/y2024/constants/calib_files/calibration_orin-7971-2-0_cam-24-01_2024-02-07_20-11-35.566609408.json
+++ b/y2024/constants/calib_files/calibration_imu-7971-0_cam-24-01_2024-03-02_19-44-12.098903651.json
@@ -12,6 +12,26 @@
   0.0,
   1.0
  ],
+ "fixed_extrinsics": {
+  "data": [
+   1.0,
+   -0.0,
+   0.0,
+   -0.131843,
+   0.0,
+   0.0,
+   1.0,
+   0.061756,
+   -0.0,
+   -1.0,
+   0.0,
+   -0.05456,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
  "dist_coeffs": [
   -0.249077,
   0.063132,
@@ -22,4 +42,4 @@
  "calibration_timestamp": 1707365495566609408,
  "camera_id": "24-01",
  "camera_number": 0
-}
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-02-07_20-45-22.787382400.json b/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-02-07_20-45-22.787382400.json
deleted file mode 100755
index 47d9435..0000000
--- a/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-02-07_20-45-22.787382400.json
+++ /dev/null
@@ -1,25 +0,0 @@
-{
- "node_name": "orin1",
- "team_number": 7971,
- "intrinsics": [
-  642.80365,
-  0.0,
-  718.017517,
-  0.0,
-  642.83667,
-  555.022461,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  -0.239969,
-  0.055889,
-  0.000086,
-  0.000099,
-  -0.005468
- ],
- "calibration_timestamp": 1707367522787382400,
- "camera_id": "24-04",
- "camera_number": 0
-}
diff --git a/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-03-02_20-09-18.016860291.json b/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-03-02_20-09-18.016860291.json
new file mode 100755
index 0000000..d60cc2a
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_orin-7971-1-0_cam-24-04_2024-03-02_20-09-18.016860291.json
@@ -0,0 +1,45 @@
+{
+ "node_name": "orin1",
+ "team_number": 7971,
+ "intrinsics": [
+  642.80365,
+  0.0,
+  718.017517,
+  0.0,
+  642.83667,
+  555.022461,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   -0.845268,
+   0.031126,
+   0.533435,
+   0.494822,
+   -0.525295,
+   0.134521,
+   -0.84022,
+   -1.212857,
+   -0.097911,
+   -0.990422,
+   -0.097356,
+   -0.319412,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.239969,
+  0.055889,
+  0.000086,
+  0.000099,
+  -0.005468
+ ],
+ "calibration_timestamp": 1709438958016860291,
+ "camera_id": "24-04",
+ "camera_number": 0
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-02-07_20-11-32.368359264.json b/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-02-07_20-11-32.368359264.json
deleted file mode 100755
index d5d2d61..0000000
--- a/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-02-07_20-11-32.368359264.json
+++ /dev/null
@@ -1,25 +0,0 @@
-{
- "node_name": "orin1",
- "team_number": 7971,
- "intrinsics": [
-  644.604858,
-  0.0,
-  752.152954,
-  0.0,
-  644.477173,
-  558.911682,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  -0.242432,
-  0.057303,
-  -0.000057,
-  0.000015,
-  -0.005636
- ],
- "calibration_timestamp": 1707365492368359264,
- "camera_id": "24-02",
- "camera_number": 1
-}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-03-02_20-09-18.022901293.json b/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-03-02_20-09-18.022901293.json
new file mode 100755
index 0000000..ed7b2f3
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_orin-7971-1-1_cam-24-02_2024-03-02_20-09-18.022901293.json
@@ -0,0 +1,45 @@
+{
+ "node_name": "orin1",
+ "team_number": 7971,
+ "intrinsics": [
+  644.604858,
+  0.0,
+  752.152954,
+  0.0,
+  644.477173,
+  558.911682,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   -0.07336,
+   0.085699,
+   0.993617,
+   0.608349,
+   -0.989433,
+   0.118683,
+   -0.083288,
+   -0.939084,
+   -0.125063,
+   -0.989227,
+   0.076087,
+   -0.35071,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.242432,
+  0.057303,
+  -0.000057,
+  0.000015,
+  -0.005636
+ ],
+ "calibration_timestamp": 1709438958022901293,
+ "camera_id": "24-02",
+ "camera_number": 1
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin-7971-2-1_cam-24-03_2024-02-07_20-40-34.928600992.json b/y2024/constants/calib_files/calibration_orin-7971-2-1_cam-24-03_2024-02-07_20-40-34.928600992.json
deleted file mode 100755
index 2a0aa00..0000000
--- a/y2024/constants/calib_files/calibration_orin-7971-2-1_cam-24-03_2024-02-07_20-40-34.928600992.json
+++ /dev/null
@@ -1,25 +0,0 @@
-{
- "node_name": "imu",
- "team_number": 7971,
- "intrinsics": [
-  648.13446,
-  0.0,
-  759.733093,
-  0.0,
-  648.40332,
-  557.951538,
-  0.0,
-  0.0,
-  1.0
- ],
- "dist_coeffs": [
-  -0.258663,
-  0.071646,
-  0.000113,
-  -0.000061,
-  -0.00879
- ],
- "calibration_timestamp": 1707367234928600992,
- "camera_id": "24-03",
- "camera_number": 1
-}
diff --git a/y2024/constants/calib_files/calibration_orin-7971-c-1_cam-24-03_2024-03-02_20-09-18.016217514.json b/y2024/constants/calib_files/calibration_orin-7971-c-1_cam-24-03_2024-03-02_20-09-18.016217514.json
new file mode 100755
index 0000000..c0847a8
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_orin-7971-c-1_cam-24-03_2024-03-02_20-09-18.016217514.json
@@ -0,0 +1,45 @@
+{
+ "node_name": "imu",
+ "team_number": 7971,
+ "intrinsics": [
+  648.13446,
+  0.0,
+  759.733093,
+  0.0,
+  648.40332,
+  557.951538,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   0.646787,
+   0.04307,
+   0.761453,
+   0.280984,
+   -0.762291,
+   0.067995,
+   0.643653,
+   -0.238549,
+   -0.024053,
+   -0.996756,
+   0.07681,
+   -0.200534,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.258663,
+  0.071646,
+  0.000113,
+  -0.000061,
+  -0.00879
+ ],
+ "calibration_timestamp": 1709438958016217514,
+ "camera_id": "24-03",
+ "camera_number": 1
+}
\ No newline at end of file
diff --git a/y2024/control_loops/superstructure/superstructure.cc b/y2024/control_loops/superstructure/superstructure.cc
index 6b262c1..dc9369e 100644
--- a/y2024/control_loops/superstructure/superstructure.cc
+++ b/y2024/control_loops/superstructure/superstructure.cc
@@ -615,6 +615,13 @@
   status_builder.add_state(state_);
   status_builder.add_uncompleted_note_goal(uncompleted_note_goal_status);
   status_builder.add_extend_ready_for_transfer(extend_at_retracted);
+  status_builder.add_extend_at_retracted(extend_at_retracted);
+  status_builder.add_turret_ready_for_load(turret_ready_for_load);
+  status_builder.add_altitude_ready_for_load(altitude_ready_for_load);
+  status_builder.add_extend_ready_for_catapult_transfer(
+      extend_ready_for_catapult_transfer);
+  status_builder.add_extend_beambreak(position->extend_beambreak());
+  status_builder.add_catapult_beambreak(position->catapult_beambreak());
 
   (void)status->Send(status_builder.Finish());
 }
diff --git a/y2024/control_loops/superstructure/superstructure_status.fbs b/y2024/control_loops/superstructure/superstructure_status.fbs
index 0420c26..8d6b14f 100644
--- a/y2024/control_loops/superstructure/superstructure_status.fbs
+++ b/y2024/control_loops/superstructure/superstructure_status.fbs
@@ -157,6 +157,23 @@
   turret_ready_for_extend_move:bool (id: 13, deprecated);
 
   uncompleted_note_goal:NoteStatus = NONE (id: 14);
+
+  // Indicates if the extend is close enough to the retracted position to be
+  // considered ready to accept note from the transfer rollers.
+  extend_at_retracted:bool (id: 15);
+
+  // Indicates if the turret is at the position to accept the note from extend
+  turret_ready_for_load:bool (id: 16);
+
+  // Indicates if the altitude is at the position to accept the note from
+  // extend
+  altitude_ready_for_load:bool (id: 17);
+
+  // Indicates if the extend is at the position to load the catapult
+  extend_ready_for_catapult_transfer:bool (id: 18);
+
+  extend_beambreak:bool (id: 19);
+  catapult_beambreak:bool (id: 20);
 }
 
 root_type Status;
diff --git a/y2024/vision/BUILD b/y2024/vision/BUILD
index aab6e64..d36c956 100644
--- a/y2024/vision/BUILD
+++ b/y2024/vision/BUILD
@@ -16,6 +16,38 @@
 )
 
 cc_binary(
+    name = "target_mapping",
+    srcs = [
+        "target_mapping.cc",
+        "vision_util.cc",
+        "vision_util.h",
+    ],
+    data = [
+        "//y2024:aos_config",
+        "//y2024/constants:constants.json",
+        "//y2024/vision:maps",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//y2023:__subpackages__"],
+    deps = [
+        "//aos:init",
+        "//aos/events:simulated_event_loop",
+        "//aos/events/logging:log_reader",
+        "//aos/util:mcap_logger",
+        "//frc971/constants:constants_sender_lib",
+        "//frc971/control_loops:pose",
+        "//frc971/vision:calibration_fbs",
+        "//frc971/vision:charuco_lib",
+        "//frc971/vision:target_mapper",
+        "//frc971/vision:vision_util_lib",
+        "//frc971/vision:visualize_robot",
+        "//third_party:opencv",
+        "//y2024/constants:constants_fbs",
+        "//y2024/constants:simulated_constants_sender",
+    ],
+)
+
+cc_binary(
     name = "image_logger",
     srcs = [
         "image_logger.cc",
diff --git a/y2024/vision/calibrate_multi_cameras.cc b/y2024/vision/calibrate_multi_cameras.cc
index f743e00..8a4bbaa 100644
--- a/y2024/vision/calibrate_multi_cameras.cc
+++ b/y2024/vision/calibrate_multi_cameras.cc
@@ -44,12 +44,14 @@
               "Type of target being used [aruco, charuco, charuco_diamond]");
 DEFINE_int32(team_number, 0,
              "Required: Use the calibration for a node with this team number");
-DEFINE_bool(use_full_logs, false,
-            "If true, extract data from logs with images");
 DEFINE_uint64(
     wait_key, 1,
     "Time in ms to wait between images (0 to wait indefinitely until click)");
 
+DEFINE_bool(robot, false,
+            "If true we're calibrating extrinsics for the robot, use the "
+            "correct node path for the robot.");
+
 DECLARE_int32(min_target_id);
 DECLARE_int32(max_target_id);
 
@@ -78,7 +80,7 @@
 namespace calibration = frc971::vision::calibration;
 
 static constexpr double kImagePeriodMs =
-    1.0 / 30.0 * 1000.0;  // Image capture period in ms
+    1.0 / 60.0 * 1000.0;  // Image capture period in ms
 
 // Change reference frame from camera to robot
 Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
@@ -97,6 +99,38 @@
   int board_id;
 };
 
+struct CameraNode {
+  std::string node_name;
+  int camera_number;
+
+  inline const std::string camera_name() const {
+    return "/" + node_name + "/camera" + std::to_string(camera_number);
+  }
+};
+
+std::vector<CameraNode> CreateNodeList() {
+  std::vector<CameraNode> list;
+
+  list.push_back({.node_name = "orin1", .camera_number = 0});
+  list.push_back({.node_name = "orin1", .camera_number = 1});
+  list.push_back({.node_name = "imu", .camera_number = 0});
+  list.push_back({.node_name = "imu", .camera_number = 1});
+
+  return list;
+}
+
+std::vector<CameraNode> node_list(CreateNodeList());
+std::map<std::string, int> CreateOrderingMap() {
+  std::map<std::string, int> map;
+
+  for (uint i = 0; i < node_list.size(); i++) {
+    map.insert({node_list.at(i).camera_name(), i});
+  }
+
+  return map;
+}
+std::map<std::string, int> ordering_map(CreateOrderingMap());
+
 TimestampedPiDetection last_observation;
 std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
     detection_list;
@@ -252,14 +286,14 @@
         kImagePeriodMs / 2.0 * 1000000.0) {
       // Sort by pi numbering, since this is how we will handle them
       std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
-      if (last_observation.pi_name < new_observation.pi_name) {
+      if (ordering_map.at(last_observation.pi_name) <
+          ordering_map.at(new_observation.pi_name)) {
         new_pair = std::pair(last_observation, new_observation);
-      } else if (last_observation.pi_name > new_observation.pi_name) {
+      } else if (ordering_map.at(last_observation.pi_name) >
+                 ordering_map.at(new_observation.pi_name)) {
         new_pair = std::pair(new_observation, last_observation);
-      } else {
-        LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
-                        "not too much of an issue???";
       }
+
       detection_list.push_back(new_pair);
 
       // This bit is just for visualization and checking purposes-- use the
@@ -366,7 +400,7 @@
 
     Eigen::Affine3d H_camera_target =
         PoseUtils::Pose3dToAffine3d(target_pose.pose);
-    VLOG(2) << node_name << " saw target " << target_pose.id
+    VLOG(1) << node_name << " saw target " << target_pose.id
             << " from TargetMap at timestamp " << distributed_eof
             << " with pose = " << H_camera_target.matrix();
   }
@@ -427,16 +461,16 @@
 
   reader.RemapLoggedChannel("/imu/constants", "y2024.Constants");
   reader.RemapLoggedChannel("/orin1/constants", "y2024.Constants");
+  if (FLAGS_robot) {
+    reader.RemapLoggedChannel("/roborio/constants", "y2024.Constants");
+  }
   reader.Register();
 
   y2024::SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
                                  FLAGS_constants_path);
 
   VLOG(1) << "Using target type " << FLAGS_target_type;
-  std::vector<std::string> node_list;
-  node_list.push_back("orin1");
-  node_list.push_back("imu");
-  std::vector<std::string> camera_list;
+
   std::vector<const calibration::CameraCalibration *> calibration_list;
 
   std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
@@ -444,86 +478,49 @@
   std::vector<frc971::vision::ImageCallback *> image_callbacks;
   std::vector<Eigen::Affine3d> default_extrinsics;
 
-  for (uint i = 0; i < node_list.size(); i++) {
-    std::string node = node_list[i];
-    const aos::Node *pi =
-        aos::configuration::GetNode(reader.configuration(), node.c_str());
+  for (const CameraNode &camera_node : node_list) {
+    const aos::Node *pi = aos::configuration::GetNode(
+        reader.configuration(), camera_node.node_name.c_str());
 
     detection_event_loops.emplace_back(
         reader.event_loop_factory()->MakeEventLoop(
-            (node + "_detection").c_str(), pi));
+            (camera_node.camera_name() + "_detection").c_str(), pi));
+    frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
+        detection_event_loops.back().get());
+    // Get the calibration for this orin/camera pair
+    const calibration::CameraCalibration *calibration =
+        y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
+                                             camera_node.node_name,
+                                             camera_node.camera_number);
+    calibration_list.push_back(calibration);
 
-    for (const std::string camera : {"/camera0", "/camera1"}) {
-      std::string camera_name = "/" + node + camera;
-      camera_list.push_back(camera_name);
-      frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
-          detection_event_loops.back().get());
+    // Extract the extrinsics from the calibration, and save as "defaults"
+    cv::Mat extrinsics_cv =
+        frc971::vision::CameraExtrinsics(calibration).value();
+    Eigen::Matrix4d extrinsics_matrix;
+    cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
+    const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
+    default_extrinsics.emplace_back(ext_H_robot_pi);
 
-      // Get the calibration for this orin/camera pair
-      int camera_id = std::stoi(camera.substr(7, 1));
-      const calibration::CameraCalibration *calibration =
-          y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
-                                               node, camera_id);
-      calibration_list.push_back(calibration);
+    VLOG(1) << "Got extrinsics for " << camera_node.camera_name() << " as\n"
+            << default_extrinsics.back().matrix();
 
-      // Extract the extrinsics from the calibration, and save as "defaults"
-      cv::Mat extrinsics_cv =
-          frc971::vision::CameraExtrinsics(calibration).value();
-      Eigen::Matrix4d extrinsics_matrix;
-      cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
-      const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
-      default_extrinsics.emplace_back(ext_H_robot_pi);
+    detection_event_loops.back()->MakeWatcher(
+        camera_node.camera_name(),
+        [&reader, &detection_event_loops, camera_node](const TargetMap &map) {
+          aos::distributed_clock::time_point pi_distributed_time =
+              reader.event_loop_factory()
+                  ->GetNodeEventLoopFactory(
+                      detection_event_loops.back().get()->node())
+                  ->ToDistributedClock(aos::monotonic_clock::time_point(
+                      aos::monotonic_clock::duration(
+                          map.monotonic_timestamp_ns())));
 
-      VLOG(1) << "Got extrinsics for " << node << ", " << camera << " as\n"
-              << default_extrinsics.back().matrix();
-
-      // If we've got full logs, we need to set up a charuco/april tag extractor
-      // nd a call back to handle the data
-      if (FLAGS_use_full_logs) {
-        frc971::vision::TargetType target_type =
-            frc971::vision::TargetTypeFromString(FLAGS_target_type);
-        frc971::vision::CharucoExtractor *charuco_ext =
-            new frc971::vision::CharucoExtractor(calibration, target_type);
-        charuco_extractors.emplace_back(charuco_ext);
-
-        LOG(INFO) << "Set up image callback for node " << node << ", camera "
-                  << camera;
-        frc971::vision::ImageCallback *image_callback =
-            new frc971::vision::ImageCallback(
-                detection_event_loops[i].get(), camera_name,
-                [&reader, &charuco_extractors, &detection_event_loops,
-                 &node_list, i](cv::Mat rgb_image,
-                                const aos::monotonic_clock::time_point eof) {
-                  aos::distributed_clock::time_point pi_distributed_time =
-                      reader.event_loop_factory()
-                          ->GetNodeEventLoopFactory(
-                              detection_event_loops[i].get()->node())
-                          ->ToDistributedClock(eof);
-                  HandleImage(detection_event_loops[i].get(), rgb_image, eof,
-                              pi_distributed_time, *charuco_extractors[i],
-                              node_list[i]);
-                });
-
-        image_callbacks.emplace_back(image_callback);
-      } else {
-        detection_event_loops[i]->MakeWatcher(
-            camera, [&reader, &detection_event_loops, camera_name,
-                     i](const TargetMap &map) {
-              aos::distributed_clock::time_point pi_distributed_time =
-                  reader.event_loop_factory()
-                      ->GetNodeEventLoopFactory(
-                          detection_event_loops[i]->node())
-                      ->ToDistributedClock(aos::monotonic_clock::time_point(
-                          aos::monotonic_clock::duration(
-                              map.monotonic_timestamp_ns())));
-
-              HandleTargetMap(map, pi_distributed_time, camera_name);
-            });
-        LOG(INFO) << "Created watcher for using the detection event loop for "
-                  << node << " with i = " << i << " and size "
-                  << detection_event_loops.size() << " and camera " << camera;
-      }
-    }
+          HandleTargetMap(map, pi_distributed_time, camera_node.camera_name());
+        });
+    LOG(INFO) << "Created watcher for using the detection event loop for "
+              << camera_node.camera_name() << " and size "
+              << detection_event_loops.size();
   }
 
   reader.event_loop_factory()->Run();
@@ -534,26 +531,27 @@
       << "Must have at least one view of both boards";
   int base_target_id = two_board_extrinsics_list[0].board_id;
   VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
-  for (auto camera : camera_list) {
+
+  for (auto camera_node : node_list) {
     std::vector<TimestampedPiDetection> pose_list;
     for (auto ext : two_board_extrinsics_list) {
       CHECK_EQ(base_target_id, ext.board_id)
           << " All boards should have same reference id";
-      if (ext.pi_name == camera) {
+      if (ext.pi_name == camera_node.camera_name()) {
         pose_list.push_back(ext);
       }
     }
     Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
-    VLOG(1) << "Estimate from " << camera << " with " << pose_list.size()
-            << " observations is:\n"
+    VLOG(1) << "Estimate from " << camera_node.camera_name() << " with "
+            << pose_list.size() << " observations is:\n"
             << avg_pose_from_pi.matrix();
   }
   Eigen::Affine3d H_boardA_boardB_avg =
       ComputeAveragePose(two_board_extrinsics_list);
   // TODO: Should probably do some outlier rejection
-  LOG(INFO) << "Estimate of two board pose using all nodes with "
-            << two_board_extrinsics_list.size() << " observations is:\n"
-            << H_boardA_boardB_avg.matrix() << "\n";
+  VLOG(1) << "Estimate of two board pose using all nodes with "
+          << two_board_extrinsics_list.size() << " observations is:\n"
+          << H_boardA_boardB_avg.matrix() << "\n";
 
   // Next, compute the relative camera poses
   LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
@@ -561,14 +559,14 @@
   std::vector<Eigen::Affine3d> updated_extrinsics;
   // Use the first node's extrinsics as our base, and fix from there
   updated_extrinsics.push_back(default_extrinsics[0]);
-  LOG(INFO) << "Default extrinsic for camera " << camera_list[0] << " is "
-            << default_extrinsics[0].matrix();
-  for (uint i = 0; i < camera_list.size() - 1; i++) {
+  LOG(INFO) << "Default extrinsic for camera " << node_list.at(0).camera_name()
+            << " is " << default_extrinsics[0].matrix();
+  for (uint i = 0; i < node_list.size() - 1; i++) {
     H_camera1_camera2_list.clear();
     // Go through the list, and find successive pairs of cameras
     for (auto [pose1, pose2] : detection_list) {
-      if ((pose1.pi_name == camera_list[i]) &&
-          (pose2.pi_name == camera_list[i + 1])) {
+      if ((pose1.pi_name == node_list.at(i).camera_name()) &&
+          (pose2.pi_name == node_list.at(i + 1).camera_name())) {
         Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
         // If pose1 isn't referenced to base_target_id, correct that
         if (pose1.board_id != base_target_id) {
@@ -616,12 +614,14 @@
     // TODO<Jim>: If we don't get any matches, we could just use default
     // extrinsics
     CHECK(H_camera1_camera2_list.size() > 0)
-        << "Failed with zero poses for node " << camera_list[i];
+        << "Failed with zero poses for node " << node_list.at(i).camera_name()
+        << " and " << node_list.at(i + 1).camera_name();
     if (H_camera1_camera2_list.size() > 0) {
       Eigen::Affine3d H_camera1_camera2_avg =
           ComputeAveragePose(H_camera1_camera2_list);
-      LOG(INFO) << "From " << camera_list[i] << " to " << camera_list[i + 1]
-                << " found " << H_camera1_camera2_list.size()
+      LOG(INFO) << "From " << node_list.at(i).camera_name() << " to "
+                << node_list.at(i + 1).camera_name() << " found "
+                << H_camera1_camera2_list.size()
                 << " observations, and the average pose is:\n"
                 << H_camera1_camera2_avg.matrix();
       Eigen::Affine3d H_camera1_camera2_default =
@@ -643,10 +643,11 @@
       Eigen::Affine3d next_extrinsic =
           updated_extrinsics.back() * H_camera1_camera2_avg;
       updated_extrinsics.push_back(next_extrinsic);
-      LOG(INFO) << "Default Extrinsic for " << camera_list[i + 1] << " is \n"
-                << default_extrinsics[i + 1].matrix();
-      LOG(INFO) << "--> Updated Extrinsic for " << camera_list[i + 1]
+      LOG(INFO) << "Default Extrinsic for " << node_list.at(i + 1).camera_name()
                 << " is \n"
+                << default_extrinsics[i + 1].matrix();
+      LOG(INFO) << "--> Updated Extrinsic for "
+                << node_list.at(i + 1).camera_name() << " is \n"
                 << next_extrinsic.matrix();
 
       // Wirte out this extrinsic to a file
@@ -686,11 +687,11 @@
       // calibration filename
       const std::string calibration_filename =
           FLAGS_output_folder +
-          absl::StrFormat("/calibration_orin-%d-%s-%d_cam-%s_%s.json",
-                          FLAGS_team_number, camera_list[i + 1].substr(5, 1),
-                          calibration_list[i + 1]->camera_number(),
-                          calibration_list[i + 1]->camera_id()->data(),
-                          time_ss.str());
+          absl::StrFormat(
+              "/calibration_orin-%d-%s-%d_cam-%s_%s.json", FLAGS_team_number,
+              node_list.at(i + 1).camera_name().substr(5, 1),
+              calibration_list[i + 1]->camera_number(),
+              calibration_list[i + 1]->camera_id()->data(), time_ss.str());
 
       LOG(INFO) << calibration_filename << " -> "
                 << aos::FlatbufferToJson(merged_calibration,
diff --git a/y2024/vision/target_mapping.cc b/y2024/vision/target_mapping.cc
new file mode 100644
index 0000000..7548445
--- /dev/null
+++ b/y2024/vision/target_mapping.cc
@@ -0,0 +1,438 @@
+#include <string>
+
+#include "Eigen/Dense"
+#include "opencv2/aruco.hpp"
+#include "opencv2/calib3d.hpp"
+#include "opencv2/core/eigen.hpp"
+#include "opencv2/features2d.hpp"
+#include "opencv2/highgui.hpp"
+#include "opencv2/highgui/highgui.hpp"
+#include "opencv2/imgproc.hpp"
+
+#include "aos/configuration.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/util/mcap_logger.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/vision/calibration_generated.h"
+#include "frc971/vision/charuco_lib.h"
+#include "frc971/vision/target_mapper.h"
+#include "frc971/vision/vision_util_lib.h"
+#include "frc971/vision/visualize_robot.h"
+#include "y2024/constants/simulated_constants_sender.h"
+#include "y2024/vision/vision_util.h"
+
+DEFINE_string(config, "",
+              "If set, override the log's config file with this one.");
+DEFINE_string(constants_path, "y2024/constants/constants.json",
+              "Path to the constant file");
+DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
+              "Write the target constraints to this path");
+DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
+              "Write the mapping stats to this path");
+DEFINE_string(field_name, "charged_up",
+              "Field name, for the output json filename and flatbuffer field");
+DEFINE_string(json_path, "y2024/vision/maps/target_map.json",
+              "Specify path for json with initial pose guesses.");
+DEFINE_double(max_pose_error, 1e-6,
+              "Throw out target poses with a higher pose error than this");
+DEFINE_double(
+    max_pose_error_ratio, 0.4,
+    "Throw out target poses with a higher pose error ratio than this");
+DEFINE_string(mcap_output_path, "", "Log to output.");
+DEFINE_string(output_dir, "y2024/vision/maps",
+              "Directory to write solved target map to");
+DEFINE_double(pause_on_distance, 2.0,
+              "Pause if two consecutive implied robot positions differ by more "
+              "than this many meters");
+DEFINE_string(orin, "orin1",
+              "Orin name to generate mcap log for; defaults to pi1.");
+DEFINE_uint64(skip_to, 1,
+              "Start at combined image of this number (1 is the first image)");
+DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
+DEFINE_int32(team_number, 0,
+             "Required: Use the calibration for a node with this team number");
+DEFINE_uint64(wait_key, 1,
+              "Time in ms to wait between images, if no click (0 to wait "
+              "indefinitely until click).");
+
+DECLARE_int32(frozen_target_id);
+DECLARE_int32(min_target_id);
+DECLARE_int32(max_target_id);
+DECLARE_bool(visualize_solver);
+
+namespace y2024::vision {
+using frc971::vision::DataAdapter;
+using frc971::vision::ImageCallback;
+using frc971::vision::PoseUtils;
+using frc971::vision::TargetMap;
+using frc971::vision::TargetMapper;
+using frc971::vision::VisualizeRobot;
+namespace calibration = frc971::vision::calibration;
+
+// Class to handle reading target poses from a replayed log,
+// displaying various debug info, and passing the poses to
+// frc971::vision::TargetMapper for field mapping.
+class TargetMapperReplay {
+ public:
+  TargetMapperReplay(aos::logger::LogReader *reader);
+
+  // Solves for the target poses with the accumulated detections if FLAGS_solve.
+  void MaybeSolve();
+
+ private:
+  static constexpr int kImageWidth = 1280;
+  // Map from pi node name to color for drawing
+  static const std::map<std::string, cv::Scalar> kOrinColors;
+  // Contains fixed target poses without solving, for use with visualization
+  static const TargetMapper kFixedTargetMapper;
+
+  // Change reference frame from camera to robot
+  static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
+                                                Eigen::Affine3d extrinsics);
+
+  // Adds april tag detections into the detection list, and handles
+  // visualization
+  void HandleAprilTags(const TargetMap &map,
+                       aos::distributed_clock::time_point node_distributed_time,
+                       std::string camera_name, Eigen::Affine3d extrinsics);
+  // Gets images from the given pi and passes apriltag positions to
+  // HandleAprilTags()
+  void HandleNodeCaptures(
+      aos::EventLoop *mapping_event_loop,
+      frc971::constants::ConstantsFetcher<y2024::Constants> *constants_fetcher,
+      int camera_number);
+
+  aos::logger::LogReader *reader_;
+  // April tag detections from all pis
+  std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
+
+  VisualizeRobot vis_robot_;
+  // Set of node names which are currently drawn on the display
+  std::set<std::string> drawn_nodes_;
+  // Number of frames displayed
+  size_t display_count_;
+  // Last time we drew onto the display image.
+  // This is different from when we actually call imshow() to update
+  // the display window
+  aos::distributed_clock::time_point last_draw_time_;
+
+  Eigen::Affine3d last_H_world_robot_;
+  // Maximum distance between consecutive T_world_robot's in one display frame,
+  // used to determine if we need to pause for the user to see this frame
+  // clearly
+  double max_delta_T_world_robot_;
+
+  std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
+
+  std::unique_ptr<aos::EventLoop> mcap_event_loop_;
+  std::unique_ptr<aos::McapLogger> relogger_;
+};
+
+const auto TargetMapperReplay::kOrinColors = std::map<std::string, cv::Scalar>{
+    {"/orin1/camera0", cv::Scalar(255, 0, 255)},
+    {"/orin1/camera1", cv::Scalar(255, 255, 0)},
+    {"/imu/camera0", cv::Scalar(0, 255, 255)},
+    {"/imu/camera1", cv::Scalar(255, 165, 0)},
+};
+
+const auto TargetMapperReplay::kFixedTargetMapper =
+    TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
+
+Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
+    Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
+  const Eigen::Affine3d H_robot_camera = extrinsics;
+  const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
+  return H_robot_target;
+}
+
+TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
+    : reader_(reader),
+      timestamped_target_detections_(),
+      vis_robot_(cv::Size(1280, 1000)),
+      drawn_nodes_(),
+      display_count_(0),
+      last_draw_time_(aos::distributed_clock::min_time),
+      last_H_world_robot_(Eigen::Matrix4d::Identity()),
+      max_delta_T_world_robot_(0.0) {
+  reader_->RemapLoggedChannel("/orin1/constants", "y2024.Constants");
+  reader_->RemapLoggedChannel("/imu/constants", "y2024.Constants");
+  reader_->Register();
+
+  SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
+                          FLAGS_constants_path);
+
+  std::vector<std::string> node_list;
+  node_list.push_back("imu");
+  node_list.push_back("orin1");
+
+  for (std::string node : node_list) {
+    const aos::Node *pi =
+        aos::configuration::GetNode(reader->configuration(), node);
+
+    mapping_event_loops_.emplace_back(
+        reader_->event_loop_factory()->MakeEventLoop(node + "_mapping_camera0",
+                                                     pi));
+    mapping_event_loops_.emplace_back(
+        reader_->event_loop_factory()->MakeEventLoop(node + "_mapping_camera1",
+                                                     pi));
+    frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
+        mapping_event_loops_[mapping_event_loops_.size() - 1].get());
+    HandleNodeCaptures(
+        mapping_event_loops_[mapping_event_loops_.size() - 2].get(),
+        &constants_fetcher, 0);
+    HandleNodeCaptures(
+        mapping_event_loops_[mapping_event_loops_.size() - 1].get(),
+        &constants_fetcher, 1);
+  }
+
+  if (FLAGS_visualize_solver) {
+    vis_robot_.ClearImage();
+    const double kFocalLength = 500.0;
+    vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
+  }
+}
+
+// Add detected apriltag poses relative to the robot to
+// timestamped_target_detections
+void TargetMapperReplay::HandleAprilTags(
+    const TargetMap &map,
+    aos::distributed_clock::time_point node_distributed_time,
+    std::string camera_name, Eigen::Affine3d extrinsics) {
+  bool drew = false;
+  std::stringstream label;
+  label << camera_name << " - ";
+
+  for (const auto *target_pose_fbs : *map.target_poses()) {
+    // Skip detections with invalid ids
+    if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
+            FLAGS_min_target_id ||
+        static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
+            FLAGS_max_target_id) {
+      VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
+      continue;
+    }
+
+    // Skip detections with high pose errors
+    if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
+      VLOG(1) << "Skipping tag " << target_pose_fbs->id()
+              << " due to pose error of " << target_pose_fbs->pose_error();
+      continue;
+    }
+    // Skip detections with high pose error ratios
+    if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
+      VLOG(1) << "Skipping tag " << target_pose_fbs->id()
+              << " due to pose error ratio of "
+              << target_pose_fbs->pose_error_ratio();
+      continue;
+    }
+
+    const TargetMapper::TargetPose target_pose =
+        PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
+
+    Eigen::Affine3d H_camera_target =
+        Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
+    Eigen::Affine3d H_robot_target =
+        CameraToRobotDetection(H_camera_target, extrinsics);
+
+    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();
+
+    if (distance_from_camera > 5.0) {
+      continue;
+    }
+
+    CHECK(map.has_monotonic_timestamp_ns())
+        << "Need detection timestamps for mapping";
+
+    timestamped_target_detections_.emplace_back(
+        DataAdapter::TimestampedDetection{
+            .time = node_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)});
+
+    if (FLAGS_visualize_solver) {
+      // If we've already drawn this camera_name in the current image,
+      // display the image before clearing and adding the new poses
+      if (drawn_nodes_.count(camera_name) != 0) {
+        display_count_++;
+        cv::putText(vis_robot_.image_,
+                    "Poses #" + std::to_string(display_count_),
+                    cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
+                    cv::Scalar(255, 255, 255));
+
+        if (display_count_ >= FLAGS_skip_to) {
+          VLOG(1) << "Showing image for node " << camera_name
+                  << " since we've drawn it already";
+          cv::imshow("View", vis_robot_.image_);
+          // Pause if delta_T is too large, but only after first image (to make
+          // sure the delta's are correct
+          if (max_delta_T_world_robot_ > FLAGS_pause_on_distance &&
+              display_count_ > 1) {
+            LOG(INFO) << "Pausing since the delta between robot estimates is "
+                      << max_delta_T_world_robot_ << " which is > threshold of "
+                      << FLAGS_pause_on_distance;
+            cv::waitKey(0);
+          } else {
+            cv::waitKey(FLAGS_wait_key);
+          }
+          max_delta_T_world_robot_ = 0.0;
+        } else {
+          VLOG(1) << "At poses #" << std::to_string(display_count_);
+        }
+        vis_robot_.ClearImage();
+        drawn_nodes_.clear();
+      }
+
+      Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
+          kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
+      Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
+      VLOG(2) << camera_name << ", id " << target_pose_fbs->id()
+              << ", t = " << node_distributed_time
+              << ", pose_error = " << target_pose_fbs->pose_error()
+              << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
+              << ", robot_pos (x,y,z) = "
+              << H_world_robot.translation().transpose();
+
+      label << "id " << target_pose_fbs->id() << ": err (% of max): "
+            << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
+            << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
+
+      vis_robot_.DrawRobotOutline(H_world_robot, camera_name,
+                                  kOrinColors.at(camera_name));
+      vis_robot_.DrawFrameAxes(H_world_target,
+                               std::to_string(target_pose_fbs->id()),
+                               kOrinColors.at(camera_name));
+
+      double delta_T_world_robot =
+          (H_world_robot.translation() - last_H_world_robot_.translation())
+              .norm();
+      max_delta_T_world_robot_ =
+          std::max(delta_T_world_robot, max_delta_T_world_robot_);
+
+      VLOG(1) << "Drew in info for robot " << camera_name << " and target #"
+              << target_pose_fbs->id();
+      drew = true;
+      last_draw_time_ = node_distributed_time;
+      last_H_world_robot_ = H_world_robot;
+    }
+  }
+  if (FLAGS_visualize_solver) {
+    if (drew) {
+      // Collect all the labels from a given node, and add the text
+      size_t pi_number =
+          static_cast<size_t>(camera_name[camera_name.size() - 1] - '0');
+      cv::putText(vis_robot_.image_, label.str(),
+                  cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN,
+                  1.0, kOrinColors.at(camera_name));
+
+      drawn_nodes_.emplace(camera_name);
+    } else if (node_distributed_time - last_draw_time_ >
+                   std::chrono::milliseconds(30) &&
+               display_count_ >= FLAGS_skip_to) {
+      cv::putText(vis_robot_.image_, "No detections", cv::Point(10, 0),
+                  cv::FONT_HERSHEY_PLAIN, 1.0, kOrinColors.at(camera_name));
+      // Display and clear the image if we haven't draw in a while
+      VLOG(1) << "Displaying image due to time lapse";
+      cv::imshow("View", vis_robot_.image_);
+      cv::waitKey(FLAGS_wait_key);
+      vis_robot_.ClearImage();
+      max_delta_T_world_robot_ = 0.0;
+      drawn_nodes_.clear();
+    }
+  }
+}
+
+void TargetMapperReplay::HandleNodeCaptures(
+    aos::EventLoop *mapping_event_loop,
+    frc971::constants::ConstantsFetcher<y2024::Constants> *constants_fetcher,
+    int camera_number) {
+  // Get the camera extrinsics
+  const auto *calibration = FindCameraCalibration(
+      constants_fetcher->constants(),
+      mapping_event_loop->node()->name()->string_view(), camera_number);
+  cv::Mat extrinsics_cv = frc971::vision::CameraExtrinsics(calibration).value();
+  Eigen::Matrix4d extrinsics_matrix;
+  cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
+  const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
+  std::string camera_name = absl::StrFormat(
+      "/%s/camera%d", mapping_event_loop->node()->name()->str(), camera_number);
+
+  mapping_event_loop->MakeWatcher(
+      camera_name.c_str(), [this, mapping_event_loop, extrinsics,
+                            camera_name](const TargetMap &map) {
+        aos::distributed_clock::time_point node_distributed_time =
+            reader_->event_loop_factory()
+                ->GetNodeEventLoopFactory(mapping_event_loop->node())
+                ->ToDistributedClock(aos::monotonic_clock::time_point(
+                    aos::monotonic_clock::duration(
+                        map.monotonic_timestamp_ns())));
+
+        HandleAprilTags(map, node_distributed_time, camera_name, extrinsics);
+      });
+}
+
+void TargetMapperReplay::MaybeSolve() {
+  if (FLAGS_solve) {
+    auto target_constraints =
+        DataAdapter::MatchTargetDetections(timestamped_target_detections_);
+
+    // Remove constraints between the two sides of the field - these are
+    // basically garbage because of how far the camera is. We will use seeding
+    // below to connect the two sides
+    target_constraints.erase(
+        std::remove_if(target_constraints.begin(), target_constraints.end(),
+                       [](const auto &constraint) {
+                         constexpr TargetMapper::TargetId kMaxRedId = 4;
+                         TargetMapper::TargetId min_id =
+                             std::min(constraint.id_begin, constraint.id_end);
+                         TargetMapper::TargetId max_id =
+                             std::max(constraint.id_begin, constraint.id_end);
+                         return (min_id <= kMaxRedId && max_id > kMaxRedId);
+                       }),
+        target_constraints.end());
+
+    LOG(INFO) << "Solving for locations of tags with "
+              << target_constraints.size() << " constraints";
+    TargetMapper mapper(FLAGS_json_path, target_constraints);
+    mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
+
+    if (!FLAGS_dump_constraints_to.empty()) {
+      mapper.DumpConstraints(FLAGS_dump_constraints_to);
+    }
+    if (!FLAGS_dump_stats_to.empty()) {
+      mapper.DumpStats(FLAGS_dump_stats_to);
+    }
+  }
+}
+
+void MappingMain(int argc, char *argv[]) {
+  std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
+
+  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(aos::logger::FindLogs(argc, argv)),
+      config.has_value() ? &config->message() : nullptr);
+
+  TargetMapperReplay mapper_replay(&reader);
+  reader.event_loop_factory()->Run();
+  mapper_replay.MaybeSolve();
+}
+
+}  // namespace y2024::vision
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+  y2024::vision::MappingMain(argc, argv);
+}
diff --git a/y2024/www/field.html b/y2024/www/field.html
index 2013cee..cfb8778 100644
--- a/y2024/www/field.html
+++ b/y2024/www/field.html
@@ -1,12 +1,27 @@
 <html>
-  <head>
-    <script src="field_main_bundle.min.js" defer></script>
-    <link rel="stylesheet" href="styles.css">
-  </head>
-  <body>
-    <div id="field"> </div>
-    <div id="legend"> </div>
-    <div id="readouts">
+
+<head>
+  <script src="field_main_bundle.min.js" defer></script>
+  <link rel="stylesheet" href="styles.css">
+</head>
+
+<body>
+  <div style="display: grid;
+  grid-template-columns: auto auto auto; gap: 5px;">
+    <div>
+      <div id="field"> </div>
+      <div id="legend"> </div>
+      <div id="vision_readouts">
+      </div>
+      <div id="message_bridge_status">
+        <div>
+          <div>Node</div>
+          <div>Client</div>
+          <div>Server</div>
+        </div>
+      </div>
+    </div>
+    <div>
       <table>
         <tr>
           <th colspan="2" style="text-align: center;">Robot State</th>
@@ -24,7 +39,6 @@
           <td id="theta"> NA </td>
         </tr>
       </table>
-
       <table>
         <tr>
           <th colspan="2" style="text-align: center;">Images</th>
@@ -34,190 +48,224 @@
           <td id="images_accepted"> NA </td>
         </tr>
       </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Superstructure States</th>
+        </tr>
+        <tr>
+          <td style="font-weight: bold;">Superstructure State</td>
+          <td id="superstructure_state" style="font-weight: bold;"> NA </td>
+        </tr>
+        <tr>
+          <td style="font-weight: bold;">Note Goal</td>
+          <td id="uncompleted_note_goal" style="font-weight: bold;"> NA </td>
+        </tr>
+        <tr>
+          <td>Catapult State</td>
+          <td id="catapult_state"> NA </td>
+        </tr>
+        <tr>
+          <td>Intake Roller State</td>
+          <td id="intake_roller_state"> NA </td>
+        </tr>
+        <tr>
+          <td>Transfer Roller State</td>
+          <td id="transfer_roller_state"> NA </td>
+        </tr>
+        <tr>
+          <td>Extend State</td>
+          <td id="extend_state"> NA </td>
+        </tr>
+        <tr>
+          <td>Extend Roller State</td>
+          <td id="extend_roller_state"> NA </td>
+        </tr>
+        <tr>
+          <th colspan="2">Beambreaks</th>
+        </tr>
+        <tr>
+          <td>Extend Beambreak</td>
+          <td id="extend_beambreak">FALSE</td>
+        </tr>
+        <tr>
+          <td>Catapult Beambreak</td>
+          <td id="catapult_beambreak">FALSE</td>
+        </tr>
+        <tr>
+          <th colspan="2">Subsytems At Position</th>
+        </tr>
+        <tr>
+          <td>Extend At Retracted Position</td>
+          <td id="extend_at_retracted">FALSE</td>
+        </tr>
+        <tr>
+          <td>Extend Ready For Transfer</td>
+          <td id="extend_ready_for_transfer">FALSE</td>
+        </tr>
+        <tr>
+          <td>Extend Ready to Transfer to Catapult</td>
+          <td id="extend_ready_for_catapult_transfer">FALSE</td>
+        </tr>
+        <tr>
+          <td>Turret at Loading Position</td>
+          <td id="turret_ready_for_load">FALSE</td>
+        </tr>
+        <tr>
+          <td>Altitude at Loading Position</td>
+          <td id="altitude_ready_for_load">FALSE</td>
+        </tr>
+      </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Aimer</th>
+        </tr>
+        <tr>
+          <td>Turret Position</td>
+          <td id="turret_position"> NA </td>
+        </tr>
+        <tr>
+          <td>Turret Velocity </td>
+          <td id="turret_velocity"> NA </td>
+        </tr>
+        <tr>
+          <td>Target Distance</td>
+          <td id="target_distance"> NA </td>
+        </tr>
+        <tr>
+          <td>Shot Distance</td>
+          <td id="shot_distance"> NA </td>
+        </tr>
+      </table>
 
-    <table>
-    <tr>
-      <th colspan="2" style="text-align: center;">Superstructure</th>
-    </tr>
-    <tr>
-      <td>Superstructure State</td>
-      <td id="superstructure_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Catapult State</td>
-      <td id="catapult_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Intake Roller State</td>
-      <td id="intake_roller_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Transfer Roller State</td>
-      <td id="transfer_roller_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Extend State</td>
-      <td id="extend_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Extend Roller State</td>
-      <td id="extend_roller_state"> NA </td>
-    </tr>
-    <tr>
-      <th colspan="2">Intake Pivot</th>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="intake_pivot"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="intake_pivot_abs"> NA </td>
-    </tr>
-    <tr>
-      <th colspan="2">Climber</th>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="climber"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="climber_abs"> NA </td>
-    </tr>
-    <tr>
-      <td>Pot Position</td>
-      <td id="climber_pot"> NA </td>
-    </tr>
-    <tr>
-      <th colspan="2">Extend</th>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="extend"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="extend_abs"> NA </td>
-    </tr>
-    <tr>
-      <td>Pot Position</td>
-      <td id="extend_pot"> NA </td>
-    </tr>
-    <tr>
-      <th colspan="2">Turret</th>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="turret"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="turret_abs"> NA </td>
-    </tr>
-    <tr>
-      <td>Pot Position</td>
-      <td id="turret_pot"> NA </td>
-    </tr>
-      <th colspan="2">Catapult</th>
-    </tr>
-    <tr>
-      <td>Catapult State</td>
-      <td id="catapult_state"> NA </td>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="catapult"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="catapult_abs"> NA </td>
-    </tr>
-    <tr>
-      <td>Pot Position</td>
-      <td id="catapult_pot"> NA </td>
-    </tr>
-    <tr>
-      <th colspan="2">Altitude</th>
-    </tr>
-    <tr>
-      <td>Position</td>
-      <td id="altitude"> NA </td>
-    </tr>
-    <tr>
-      <td>Absolute Position</td>
-      <td id="altitude_abs"> NA </td>
-    </tr>
-    <tr>
-      <td>Pot Position</td>
-      <td id="altitude_pot"> NA </td>
-    </tr>
-    </table>
-    <table>
-    <tr>
-      <th colspan="2" style="text-align: center;">Aimer</th>
-    </tr>
-    <tr>
-      <td>Turret Position</td>
-      <td id="turret_position"> NA </td>
-    </tr>
-    <tr>
-      <td>Turret Velocity </td>
-      <td id="turret_velocity"> NA </td>
-    </tr>
-    <tr>
-      <td>Target Distance</td>
-      <td id="target_distance"> NA </td>
-    </tr>
-    <tr>
-      <td>Shot Distance</td>
-      <td id="shot_distance"> NA </td>
-    </tr>
-  </table>
-
-  <h3>Zeroing Faults:</h3>
-  <p id="zeroing_faults"> NA </p>
-  </div>
-  <div id="middle_readouts">
-    <div id="vision_readouts">
+      <h3>Zeroing Faults:</h3>
+      <p id="zeroing_faults"> NA </p>
     </div>
-    <div id="message_bridge_status">
-      <div>
-        <div>Node</div>
-        <div>Client</div>
-        <div>Server</div>
-      </div>
+    <div>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Subsystems</th>
+        </tr>
+        <tr>
+          <th colspan="2">Intake Pivot</th>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="intake_pivot"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="intake_pivot_abs"> NA </td>
+        </tr>
+        <tr>
+          <th colspan="2">Climber</th>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="climber"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="climber_abs"> NA </td>
+        </tr>
+        <tr>
+          <td>Pot Position</td>
+          <td id="climber_pot"> NA </td>
+        </tr>
+        <tr>
+          <th colspan="2">Extend</th>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="extend"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="extend_abs"> NA </td>
+        </tr>
+        <tr>
+          <td>Pot Position</td>
+          <td id="extend_pot"> NA </td>
+        </tr>
+        <tr>
+          <th colspan="2">Turret</th>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="turret"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="turret_abs"> NA </td>
+        </tr>
+        <tr>
+          <td>Pot Position</td>
+          <td id="turret_pot"> NA </td>
+        </tr>
+        <th colspan="2">Catapult</th>
+        </tr>
+        <tr>
+          <td>Catapult State</td>
+          <td id="catapult_state"> NA </td>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="catapult"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="catapult_abs"> NA </td>
+        </tr>
+        <tr>
+          <td>Pot Position</td>
+          <td id="catapult_pot"> NA </td>
+        </tr>
+        <tr>
+          <th colspan="2">Altitude</th>
+        </tr>
+        <tr>
+          <td>Position</td>
+          <td id="altitude"> NA </td>
+        </tr>
+        <tr>
+          <td>Absolute Position</td>
+          <td id="altitude_abs"> NA </td>
+        </tr>
+        <tr>
+          <td>Pot Position</td>
+          <td id="altitude_pot"> NA </td>
+        </tr>
+      </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;"> Drivetrain Encoder Positions </th>
+        </tr>
+        <tr>
+          <td> Left Encoder Position</td>
+          <td id="left_drivetrain_encoder"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Encoder Position</td>
+          <td id="right_drivetrain_encoder"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Front Falcon CAN Position</td>
+          <td id="falcon_right_front"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Back Falcon CAN Position</td>
+          <td id="falcon_right_back"> NA </td>
+        </tr>
+        <tr>
+          <td> Left Front Falcon CAN Position</td>
+          <td id="falcon_left_front"> NA </td>
+        </tr>
+        <tr>
+          <td> Left Back Falcon CAN Position</td>
+          <td id="falcon_left_back"> NA </td>
+        </tr>
+      </table>
     </div>
   </div>
-  <table>
-      <tr>
-        <th colspan="2" style="text-align: center;"> Drivetrain Encoder Positions </th>
-      </tr>
-      <tr>
-        <td> Left Encoder Position</td>
-        <td id="left_drivetrain_encoder"> NA </td>
-      </tr>
-      <tr>
-        <td> Right Encoder Position</td>
-        <td id="right_drivetrain_encoder"> NA </td>
-      </tr>
-      <tr>
-        <td> Right Front Falcon CAN Position</td>
-        <td id="falcon_right_front"> NA </td>
-      </tr>
-      <tr>
-        <td> Right Back Falcon CAN Position</td>
-        <td id="falcon_right_back"> NA </td>
-      </tr>
-      <tr>
-        <td> Left Front Falcon CAN Position</td>
-        <td id="falcon_left_front"> NA </td>
-      </tr>
-      <tr>
-        <td> Left Back Falcon CAN Position</td>
-        <td id="falcon_left_back"> NA </td>
-      </tr>
-  </table>
-  </body>
-</html>
+</body>
 
+</html>
\ No newline at end of file
diff --git a/y2024/www/field_handler.ts b/y2024/www/field_handler.ts
index 555df93..949b34b 100644
--- a/y2024/www/field_handler.ts
+++ b/y2024/www/field_handler.ts
@@ -6,7 +6,7 @@
 import {Position as DrivetrainPosition} from '../../frc971/control_loops/drivetrain/drivetrain_position_generated'
 import {CANPosition as DrivetrainCANPosition} from '../../frc971/control_loops/drivetrain/drivetrain_can_position_generated'
 import {Status as DrivetrainStatus} from '../../frc971/control_loops/drivetrain/drivetrain_status_generated'
-import {SuperstructureState, IntakeRollerStatus, CatapultState, TransferRollerStatus, ExtendRollerStatus, ExtendStatus, Status as SuperstructureStatus} from '../control_loops/superstructure/superstructure_status_generated'
+import {SuperstructureState, IntakeRollerStatus, CatapultState, TransferRollerStatus, ExtendRollerStatus, ExtendStatus, NoteStatus, Status as SuperstructureStatus} from '../control_loops/superstructure/superstructure_status_generated'
 import {LocalizerOutput} from '../../frc971/control_loops/drivetrain/localization/localizer_output_generated'
 import {TargetMap} from '../../frc971/vision/target_map_generated'
 
@@ -51,6 +51,25 @@
     (document.getElementById('extend_roller_state') as HTMLElement);
   private catapultState: HTMLElement =
     (document.getElementById('catapult_state') as HTMLElement);
+  private uncompletedNoteGoal: HTMLElement =
+  (document.getElementById('uncompleted_note_goal') as HTMLElement);
+
+  private extend_beambreak: HTMLElement =
+  (document.getElementById('extend_beambreak') as HTMLElement);
+  private catapult_beambreak: HTMLElement =
+  (document.getElementById('catapult_beambreak') as HTMLElement);
+
+  private extend_at_retracted: HTMLElement =
+  (document.getElementById('extend_at_retracted') as HTMLElement);
+  private extend_ready_for_transfer: HTMLElement =
+  (document.getElementById('extend_ready_for_transfer') as HTMLElement);
+  private extend_ready_for_catapult_transfer: HTMLElement =
+  (document.getElementById('extend_ready_for_catapult_transfer') as HTMLElement);
+  private turret_ready_for_load: HTMLElement =
+  (document.getElementById('turret_ready_for_load') as HTMLElement);
+  private altitude_ready_for_load: HTMLElement =
+  (document.getElementById('altitude_ready_for_load') as HTMLElement);
+
 
   private intakePivot: HTMLElement =
     (document.getElementById('intake_pivot') as HTMLElement);
@@ -257,6 +276,18 @@
     div.classList.remove('zeroing');
     div.classList.remove('near');
   }
+
+  setBoolean(div: HTMLElement, triggered: boolean): void {
+    div.innerHTML = ((triggered) ? "TRUE" : "FALSE")
+    if (triggered) {
+      div.classList.remove('false');
+      div.classList.add('true');
+    } else {
+      div.classList.remove('true');
+      div.classList.add('false');
+    }
+  }
+
   draw(): void {
     this.reset();
     this.drawField();
@@ -275,6 +306,22 @@
         ExtendRollerStatus[this.superstructureStatus.extendRoller()];
       this.catapultState.innerHTML =
         CatapultState[this.superstructureStatus.shooter().catapultState()];
+      this.uncompletedNoteGoal.innerHTML =
+        NoteStatus[this.superstructureStatus.uncompletedNoteGoal()];
+
+      this.setBoolean(this.extend_beambreak, this.superstructureStatus.extendBeambreak());
+
+      this.setBoolean(this.catapult_beambreak, this.superstructureStatus.catapultBeambreak());
+
+      this.setBoolean(this.extend_ready_for_transfer, this.superstructureStatus.extendReadyForTransfer());
+
+      this.setBoolean(this.extend_at_retracted, this.superstructureStatus.extendAtRetracted());
+
+      this.setBoolean(this.turret_ready_for_load, this.superstructureStatus.turretReadyForLoad());
+
+      this.setBoolean(this.altitude_ready_for_load, this.superstructureStatus.altitudeReadyForLoad());
+
+      this.setBoolean(this.extend_ready_for_catapult_transfer, this.superstructureStatus.extendReadyForCatapultTransfer());
 
       if (this.superstructureStatus.shooter() &&
           this.superstructureStatus.shooter().aimer()) {
diff --git a/y2024/www/styles.css b/y2024/www/styles.css
index 6193a57..39b7519 100644
--- a/y2024/www/styles.css
+++ b/y2024/www/styles.css
@@ -15,7 +15,6 @@
   float: right;
 }
 
-
 #legend {
   display: inline-block;
 }
@@ -26,7 +25,7 @@
   padding: 5px;
   margin: 10px;
   table-layout: fixed;
-  width: 450px;
+  width: 100%;
   overflow: hidden;
 }
 
@@ -141,3 +140,11 @@
   flex: 1;
   width: 100%;
 }
+
+.true {
+  background-color: LightGreen;
+}
+
+.false {
+  background-color: red;
+}