From 09ca417a8bb68e19d9901d43554cbde64dd54c8c Mon Sep 17 00:00:00 2001 From: Tony Wu Date: Wed, 26 Feb 2025 11:24:39 -0800 Subject: [PATCH 01/60] cam 1 & 2 construction and nt table camera selectr --- .OutlineViewer/outlineviewer.json | 32 +++++++++ src/main/java/frc/robot/RobotContainer.java | 73 +++++++++++++++++++++ 2 files changed, 105 insertions(+) diff --git a/.OutlineViewer/outlineviewer.json b/.OutlineViewer/outlineviewer.json index bee31742..91c7a425 100644 --- a/.OutlineViewer/outlineviewer.json +++ b/.OutlineViewer/outlineviewer.json @@ -3,9 +3,41 @@ "mode": "Client (NT4)", "serverTeam": "192" }, + "Retained Values": { + "open": false + }, "transitory": { + "MotorStats": { + "open": true + }, + "PathPlanner": { + "open": true + }, + "Shuffleboard": { + "open": true + }, + "SmartDashboard": { + "open": true + }, "Swerve": { "open": true + }, + "SwerveStats": { + "Pose2d##v_/SwerveStats/estimatedPose": { + "Rotation2d##v_rotation": { + "open": true + }, + "Translation2d##v_translation": { + "open": true + }, + "open": true + }, + "open": true + }, + "photonvision": { + "Arducam_OV9281_USB_Camera": { + "open": true + } } } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 813c6854..cf9956ab 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -9,8 +9,17 @@ import frc.robot.controllers.PS5DriveController; import frc.robot.controllers.XboxDriveController; +import java.util.EnumSet; + import com.pathplanner.lib.commands.PathPlannerAuto; +import edu.wpi.first.cscore.MjpegServer; +import edu.wpi.first.cscore.UsbCamera; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEntry; +import edu.wpi.first.networktables.NetworkTableEvent; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.util.PixelFormat; import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.Command; @@ -35,12 +44,25 @@ public class RobotContainer { private final FieldManagementSubsystem fieldManagementSubsystem = new FieldManagementSubsystem(); private final PhoenixLoggingSubsystem phoenixLoggingSubsystem = new PhoenixLoggingSubsystem(fieldManagementSubsystem); + + //driver camera stuff: + private UsbCamera driverCamera; + private MjpegServer driverCameraServer; + private UsbCamera driverCamera2; + + private NetworkTableInstance ntInstance; + private NetworkTable testTable; + private NetworkTable FMStable; + private NetworkTableEntry cameraSelectionEntry; /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); startLog(); configureBindings(); + constructDriverCameras(); + constructNetworkTableListeners(); + } /** @@ -113,4 +135,55 @@ private void startLog(){ DriverStation.startDataLog(DataLogManager.getLog()); } + + public void constructDriverCameras(){ + try { + driverCamera = new UsbCamera("fisheye", 0); + driverCamera.setVideoMode(PixelFormat.kMJPEG, 160, 120, 30); + driverCamera.setExposureManual(40); + driverCameraServer = new MjpegServer("m1", 1181); + driverCameraServer.setSource(driverCamera); + } catch (Exception e) { + System.out.print(e); + } + try { + driverCamera2 = new UsbCamera("fisheye2", 1); + driverCamera2.setVideoMode(PixelFormat.kMJPEG, 160, 120, 30); + driverCamera2.setExposureManual(40); + } catch (Exception e) { + System.out.print(e); + } + } + + public void constructNetworkTableListeners(){ + + ntInstance = NetworkTableInstance.getDefault(); + FMStable = ntInstance.getTable("FMSInfo"); + testTable = ntInstance.getTable("testTable"); + + //allianceEntry = FMStable.getEntry("IsRedAlliance"); + cameraSelectionEntry = testTable.getEntry("cameraSelection"); + // FMStable.addListener("IsRedAlliance", EnumSet.of(NetworkTableEvent.Kind.kValueAll), (table, key, event) -> { + + // }); + testTable.addListener("cameraSelection", EnumSet.of(NetworkTableEvent.Kind.kValueAll), (table, key, event) ->{ + if (event.valueData.value.getBoolean()){ + //server1.setSource(camera1); + driverCameraServer.setSource(driverCamera); + + System.out.println("CAMERA1!"); + } + else{ + //server1.setSource(camera2); + driverCameraServer.setSource(driverCamera2); + + System.out.println("CAMERA2!"); + + } + }); + + } + + + } From 9b36991069bc7d4c3cea0c04cb657497d6f7e563 Mon Sep 17 00:00:00 2001 From: Tony Wu Date: Wed, 26 Feb 2025 12:06:44 -0800 Subject: [PATCH 02/60] cam constants added --- .OutlineViewer/outlineviewer.json | 32 ++++++++++++++++++++++++++ src/main/java/frc/robot/Constants.java | 18 +++++++-------- 2 files changed, 41 insertions(+), 9 deletions(-) diff --git a/.OutlineViewer/outlineviewer.json b/.OutlineViewer/outlineviewer.json index bee31742..91c7a425 100644 --- a/.OutlineViewer/outlineviewer.json +++ b/.OutlineViewer/outlineviewer.json @@ -3,9 +3,41 @@ "mode": "Client (NT4)", "serverTeam": "192" }, + "Retained Values": { + "open": false + }, "transitory": { + "MotorStats": { + "open": true + }, + "PathPlanner": { + "open": true + }, + "Shuffleboard": { + "open": true + }, + "SmartDashboard": { + "open": true + }, "Swerve": { "open": true + }, + "SwerveStats": { + "Pose2d##v_/SwerveStats/estimatedPose": { + "Rotation2d##v_rotation": { + "open": true + }, + "Translation2d##v_translation": { + "open": true + }, + "open": true + }, + "open": true + }, + "photonvision": { + "Arducam_OV9281_USB_Camera": { + "open": true + } } } } diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 71d39e5e..23c08cf8 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -112,26 +112,26 @@ public static class VisionConstants{ public static final CameraConfig[] cameraConfigs = new CameraConfig[]{ new CameraConfig( - "1", + "7", new Transform3d( - 0.31, 0.01, 0.2, - new Rotation3d(- Math.PI / 2., 0, 0) + -0.019, -0.071, 0.981, + new Rotation3d(0, -Math.PI/6., Math.PI) ), PoseStrategy.LOWEST_AMBIGUITY ), new CameraConfig( - "2", + "3", new Transform3d( - 0.0508, -0.0476,1.13, - new Rotation3d(Math.PI, -Math.PI * 8. / 9., 0.) + 0.031, -0.071,0.981, + new Rotation3d(0, -Math.PI * 6., 0) ), PoseStrategy.LOWEST_AMBIGUITY ), new CameraConfig( - "3", + "4", new Transform3d(//11.3 in above ground - 0.211, -0.2695, 0.28702 , - new Rotation3d(0, 0., Math.PI / 180. * 19.) + 0.235, -0.286, 0.220 , + new Rotation3d(0, -Math.PI/9., Math.PI / 9.) ), PoseStrategy.LOWEST_AMBIGUITY ), From 28c15cbfeca93dc738ae9be208807524be7d2974 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 20 Feb 2025 16:35:38 -0800 Subject: [PATCH 03/60] Update krakens to torque current FOC control --- src/main/java/frc/robot/util/LoggedTalon.java | 304 ++++++++++++++++++ 1 file changed, 304 insertions(+) create mode 100644 src/main/java/frc/robot/util/LoggedTalon.java diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java new file mode 100644 index 00000000..a78f67f4 --- /dev/null +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -0,0 +1,304 @@ +package frc.robot.util; + +import java.util.EnumSet; + +import com.ctre.phoenix6.StatusCode; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; +import com.ctre.phoenix6.hardware.TalonFX; + +import edu.wpi.first.networktables.DoublePublisher; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEvent; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.util.datalog.DoubleLogEntry; +import edu.wpi.first.wpilibj.DataLogManager; + +import static frc.robot.Constants.DebugConstants.MASTER_DEBUG; +public class LoggedTalon{ + + private final TalonFX motor; + + private final int canId; + private double[] pidsvg = new double[6]; + + private NetworkTableInstance ntInstance; + private NetworkTable motorStatsTable; + + private DoublePublisher positionPublisher; + private DoublePublisher veloPublisher; + private DoublePublisher appliedVlotsPublisher; + private DoublePublisher supplyCurrentPublisher; + private DoublePublisher statorCurrentPublisher; + private DoublePublisher temperaturePublisher; + private DoublePublisher targetPositionPublisher; + private DoublePublisher targetVelocityPublisher; + + private DoubleLogEntry positionLogEntry; + private DoubleLogEntry veloLogEntry; + private DoubleLogEntry appliedVoltsLogEntry; + private DoubleLogEntry supplyCurrLogEntry; + private DoubleLogEntry statorCurrLogEntry; + private DoubleLogEntry temperatureLogEntry; + private DoubleLogEntry targetPositionLogEntry; + private DoubleLogEntry targetVelocityLogEntry; + + private double targetPosition; + private double targetVelocity; + + public LoggedTalon( + int canId, String canBusName, TalonFXConfiguration talonConfig + ){ + motor = new TalonFX(canId, canBusName); + for (int i = 0; i < 4; i++) { + boolean error = + motor.getConfigurator() + .apply(talonConfig, 0.1) + == StatusCode.OK; + if (!error) break; + } + this.canId = canId; + pidsvg = new double[] { + talonConfig.Slot0.kP, + talonConfig.Slot0.kI, + talonConfig.Slot0.kD, + talonConfig.Slot0.kS, + talonConfig.Slot0.kV, + talonConfig.Slot0.kG + }; + initNT(canId); + initLogs(canId); + if(MASTER_DEBUG){ + enableDebug(); + } + } + + /** + * Sets the motor's position reference + * @param position position reference + */ + public void setPositionReference(double position){ + targetPosition = position; + motor.setControl(new PositionTorqueCurrentFOC(position)); + } + + /** + * Sets the motor's position reference with feedforward + * @param position position reference + * @param arbFF arbitrary feedforward + */ + public void setPositionReferenceWithArbFF(double position, double arbFF){ + targetPosition = position; + motor.setControl( + new PositionTorqueCurrentFOC(position).withFeedForward(arbFF) + ); + } + /** + * Set the motor's velocity reference + * @param velocity velocity reference + */ + public void setVelocityReference(double velocity){ + targetVelocity = velocity; + motor.setControl(new VelocityTorqueCurrentFOC(velocity)); + } + + /** + * Sets the motor's position to a certain value + * @param position mechanisam position after taking the position conversion + * into account + */ + public void setPosition(double position){ + for (int i = 0; i < 4; i++) { + boolean error = motor.setPosition(position) == StatusCode.OK; + if (!error) break; + } + } + + /** + * Configures drive motor's PIDSV + * @param p kP + * @param i kI + * @param d kD + * @param s kS for static friction + * @param v kV Voltage feed forward + */ + public void configurePIDSVG(double p, double i, double d, double s, double v, + double g + ) { + Slot0Configs slot0Configs = new Slot0Configs(); + + slot0Configs.kP = p; + slot0Configs.kI = i; + slot0Configs.kD = d; + slot0Configs.kS = s; + slot0Configs.kV = v; + slot0Configs.kG = g; + + motor.getConfigurator().apply(slot0Configs); + } + + /** + * initializes network table and entries + * @param canId motor's CAN ID + */ + private void initNT(int canId){ + ntInstance = NetworkTableInstance.getDefault(); + motorStatsTable = ntInstance.getTable("MotorStats"); + + positionPublisher = motorStatsTable.getDoubleTopic( + canId + "position" + ).publish(); + + veloPublisher = motorStatsTable.getDoubleTopic(canId + "velo").publish(); + + appliedVlotsPublisher = motorStatsTable.getDoubleTopic( + canId + "appliedVolts" + ).publish(); + + supplyCurrentPublisher = motorStatsTable.getDoubleTopic( + canId + "supplyCurrent" + ).publish(); + + statorCurrentPublisher = motorStatsTable.getDoubleTopic( + canId + "statorCurrent" + ).publish(); + + temperaturePublisher = motorStatsTable.getDoubleTopic( + canId + "temperature" + ).publish(); + + targetPositionPublisher = motorStatsTable.getDoubleTopic( + canId + "targetPosition" + ).publish(); + + targetVelocityPublisher = motorStatsTable.getDoubleTopic( + canId + "targetVelocity" + ).publish(); + } + + /** + * Initializes log entries + * @param canId drive motor's CAN ID + */ + private void initLogs(int canId){ + positionLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "position" + ); + + veloLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "velo" + ); + + appliedVoltsLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "appliedVolts" + ); + + supplyCurrLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "supplyCurrent" + ); + + statorCurrLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "statorCurrent" + ); + + temperatureLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "temperature" + ); + + targetPositionLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetPosition" + ); + + targetVelocityLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetVelocity" + ); + } + + /** + * Allows changing PID through NT + */ + public void enableDebug(){ + motorStatsTable.getDoubleArrayTopic(canId + "PIDSVG").publish().set( + pidsvg + ); + motorStatsTable.addListener(canId + "PIDSVG", + EnumSet.of(NetworkTableEvent.Kind.kValueAll), + (table, key, event) -> { + configurePIDSVG( + event.valueData.value.getDoubleArray()[0], + event.valueData.value.getDoubleArray()[1], + event.valueData.value.getDoubleArray()[2], + event.valueData.value.getDoubleArray()[3], + event.valueData.value.getDoubleArray()[4], + event.valueData.value.getDoubleArray()[5] + ); + } + ); + } + /** + * Gets motor's position in rotations after taking the + * SensorToMechanismRatio into account + * @return position of the motor in rotations + */ + public double getPosition(){ + return motor.getPosition().getValueAsDouble(); + } + + /** + * Gets motor's velocity in RPS after taking the SensorToMechanismRatio into + * account + * @return velocity of the motor in RPS + */ + public double getVelocity(){ + return motor.getVelocity().getValueAsDouble(); + } + + /** + * Publishes motor stats to NT for logging + */ + public void publishStats(){ + positionPublisher.set(motor.getPosition().getValueAsDouble()); + veloPublisher.set(motor.getVelocity().getValueAsDouble()); + appliedVlotsPublisher.set(motor.getMotorVoltage().getValueAsDouble()); + supplyCurrentPublisher.set(motor.getSupplyCurrent().getValueAsDouble()); + statorCurrentPublisher.set(motor.getStatorCurrent().getValueAsDouble()); + temperaturePublisher.set(motor.getDeviceTemp().getValueAsDouble()); + targetPositionPublisher.set(targetPosition); + targetVelocityPublisher.set(targetVelocity); + } + + /** + * Loggs motor stats into log file + */ + public void logStats(){ + positionLogEntry.append( + motor.getPosition().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + veloLogEntry.append( + motor.getVelocity().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + appliedVoltsLogEntry.append( + motor.getMotorVoltage().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + supplyCurrLogEntry.append( + motor.getSupplyCurrent().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + statorCurrLogEntry.append( + motor.getStatorCurrent().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + temperatureLogEntry.append( + motor.getDeviceTemp().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + targetPositionLogEntry.append(targetPosition, GRTUtil.getFPGATime()); + + targetVelocityLogEntry.append(targetVelocity, GRTUtil.getFPGATime()); + } +} \ No newline at end of file From 9208dd9dbe34d94ca811ef198ad79927f54dcc02 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 20 Feb 2025 16:35:47 -0800 Subject: [PATCH 04/60] Add debug constant --- src/main/java/frc/robot/Constants.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 23c08cf8..4e3eb6b6 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -84,6 +84,10 @@ public static class LoggingConstants{ public static final String SWERVE_TABLE = "SwerveStats"; } + public static class DebugConstants{ + public static final boolean MASTER_DEBUG = true; + } + public static class VisionConstants{ public static final double FIELD_X = 17.5482504; From 5a6dcb6746de5d3267b2f7153dcd161e103e1ab1 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 13:39:10 -0800 Subject: [PATCH 05/60] Publishes & logs close loop error --- src/main/java/frc/robot/util/LoggedTalon.java | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index a78f67f4..e35e078f 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -35,6 +35,7 @@ public class LoggedTalon{ private DoublePublisher temperaturePublisher; private DoublePublisher targetPositionPublisher; private DoublePublisher targetVelocityPublisher; + private DoublePublisher closedLoopErrorPublisher; private DoubleLogEntry positionLogEntry; private DoubleLogEntry veloLogEntry; @@ -44,6 +45,7 @@ public class LoggedTalon{ private DoubleLogEntry temperatureLogEntry; private DoubleLogEntry targetPositionLogEntry; private DoubleLogEntry targetVelocityLogEntry; + private DoubleLogEntry closedLoopErrorLogEntry; private double targetPosition; private double targetVelocity; @@ -176,6 +178,10 @@ private void initNT(int canId){ targetVelocityPublisher = motorStatsTable.getDoubleTopic( canId + "targetVelocity" ).publish(); + + closedLoopErrorPublisher = motorStatsTable.getDoubleTopic( + canId + "closedLoopError" + ).publish(); } /** @@ -214,6 +220,10 @@ private void initLogs(int canId){ targetVelocityLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "targetVelocity" ); + + closedLoopErrorLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "closedLoopError" + ); } /** @@ -255,6 +265,13 @@ public double getVelocity(){ return motor.getVelocity().getValueAsDouble(); } + /** + * Gets motor's closed loop error + * @return closed loop error + */ + public double getCloseLoopError(){ + return motor.getClosedLoopError().getValueAsDouble(); + } /** * Publishes motor stats to NT for logging */ From 97dd67765fab5a7aab18ab8f8bbb0ad643ea8946 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 14:11:31 -0800 Subject: [PATCH 06/60] Fix naming --- src/main/java/frc/robot/util/LoggedTalon.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index e35e078f..c6525bb0 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -247,6 +247,7 @@ public void enableDebug(){ } ); } + /** * Gets motor's position in rotations after taking the * SensorToMechanismRatio into account @@ -269,9 +270,10 @@ public double getVelocity(){ * Gets motor's closed loop error * @return closed loop error */ - public double getCloseLoopError(){ + public double getClosedLoopError(){ return motor.getClosedLoopError().getValueAsDouble(); } + /** * Publishes motor stats to NT for logging */ From 3b08fd4bf471d627db8db53f283f992fbb115e4d Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 14:15:28 -0800 Subject: [PATCH 07/60] publish & log closed loop error --- src/main/java/frc/robot/util/LoggedTalon.java | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index c6525bb0..a509f818 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -286,6 +286,7 @@ public void publishStats(){ temperaturePublisher.set(motor.getDeviceTemp().getValueAsDouble()); targetPositionPublisher.set(targetPosition); targetVelocityPublisher.set(targetVelocity); + closedLoopErrorPublisher.set(motor.getClosedLoopError().getValueAsDouble()); } /** @@ -319,5 +320,9 @@ public void logStats(){ targetPositionLogEntry.append(targetPosition, GRTUtil.getFPGATime()); targetVelocityLogEntry.append(targetVelocity, GRTUtil.getFPGATime()); + + closedLoopErrorLogEntry.append( + motor.getClosedLoopError().getValueAsDouble(), GRTUtil.getFPGATime() + ); } } \ No newline at end of file From b00b241d944c81d03e3c859a4badf0b72061e747 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 14:21:18 -0800 Subject: [PATCH 08/60] Untested Kraken Intake --- .../Intake/Pivot/PivotToSourceCommand.java | 25 ++++++ .../Intake/Roller/RollerOnCommand.java | 26 +++++++ src/main/java/frc/robot/Constants.java | 44 +++++++++++ .../Intake/Pivot/PivotSubsystem.java | 76 +++++++++++++++++++ .../Intake/Roller/RollerSubsystem.java | 59 ++++++++++++++ 5 files changed, 230 insertions(+) create mode 100644 src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java create mode 100644 src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java create mode 100644 src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java create mode 100644 src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java new file mode 100644 index 00000000..8ce33956 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Intake.Pivot; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; + +public class PivotToSourceCommand extends Command{ + private final PivotSubsystem pivotSubsystem; + + public PivotToSourceCommand(PivotSubsystem pivotSubsystem){ + this.pivotSubsystem = pivotSubsystem; + this.addRequirements(pivotSubsystem); + } + + @Override + public void initialize(){ + pivotSubsystem.setPositionReference(PivotConstants.SOURCE_POS); + } + + @Override + public boolean isFinished(){ + return Math.abs(pivotSubsystem.getClosedLoopError()) + < PivotConstants.PIVOT_TOLERANCE; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java new file mode 100644 index 00000000..c15b198b --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java @@ -0,0 +1,26 @@ +package frc.robot.Commands.Intake.Roller; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.subsystems.Intake.Roller.RollerSubsystem; + +public class RollerOnCommand extends Command{ + + private final RollerSubsystem rollerSubsystem; + + public RollerOnCommand(RollerSubsystem rollerSubsystem){ + this.rollerSubsystem = rollerSubsystem; + this.addRequirements(rollerSubsystem); + } + + @Override + public void initialize(){ + rollerSubsystem.setRollerSpeed(RollerConstants.ROLLER_ON_SPEED); + } + + @Override + public boolean isFinished(){ + return Math.abs(rollerSubsystem.getClosedLoopError()) + < RollerConstants.ROLLER_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4e3eb6b6..3582a2c8 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -27,6 +27,48 @@ public static class OperatorConstants { public static final int kDriverControllerPort = 0; } + public static class IntakeConstans{ + + public static class PivotConstants{ + public static final int PIVOT_CAN_ID = 1; + + public static final double PIVOT_KP = 0.; + public static final double PIVOT_KI = 0.; + public static final double PIVOT_KD = 0.; + public static final double PIVOT_KG = 0.; + public static final double PIVOT_KV = 0.; + + public static final double SOURCE_POS = 0.; + + public static final double PIVOT_TOLERANCE = 0.1; + + public static final double ROTOR_TO_SENSOR_RATIO = 0.; + public static final double PIVOT_INIT_POS = 90.; + public static final double PIVOT_MAX_POS = 90.; + public static final double PIVOT_MIN_POS = -90.; + + public static final double PIVOT_RAMP_RATE = 0.02; + public static final double PIVOT_CURRENT_LIMIT = 100.; + } + + public static class RollerConstants{ + public static final int ROLLER_CAN_ID = 0; + public static final double ROLLER_SPEED = 0.5; + public static final double ROLLER_KP = 0; + public static final double ROLLER_KI = 0; + public static final double ROLLER_KD = 0; + public static final double ROLLER_KS = 0; + public static final double ROLLER_KV = 0; + + public static final double ROLLER_ON_SPEED = 0.5; + public static final double ROLLER_OFF_SPEED = 0; + public static final double ROLLER_TOLERANCE = 0.1; + + public static final double ROLLER_RAMP_RATE = 0.02; + public static final double ROLLER_CURRENT_LIMIT = 100.; + } + } + /** Constants for the swerve subsystem. */ public static class SwerveConstants { public static final int FL_DRIVE = 0; @@ -86,6 +128,8 @@ public static class LoggingConstants{ public static class DebugConstants{ public static final boolean MASTER_DEBUG = true; + public static final boolean PIVOT_DEBUG = true; + public static final boolean ROLLER_DEBUG = true; } public static class VisionConstants{ diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java new file mode 100644 index 00000000..e85c03a9 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -0,0 +1,76 @@ +package frc.robot.subsystems.Intake.Pivot; + +import com.ctre.phoenix6.configs.ClosedLoopGeneralConfigs; +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.FeedbackConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.SoftwareLimitSwitchConfigs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.GravityTypeValue; + +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.DebugConstants; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.util.LoggedTalon; + +public class PivotSubsystem extends SubsystemBase{ + + private LoggedTalon pivotMotor; + + private TalonFXConfiguration pivotConfig = new TalonFXConfiguration() + .withSlot0( + new Slot0Configs() + .withKP(PivotConstants.PIVOT_KP) + .withKI(PivotConstants.PIVOT_KI) + .withKD(PivotConstants.PIVOT_KD) + .withKG(PivotConstants.PIVOT_KG) + .withKV(PivotConstants.PIVOT_KV) + .withGravityType(GravityTypeValue.Arm_Cosine) + ) + .withClosedLoopGeneral( + new ClosedLoopGeneralConfigs() + .withContinuousWrap(true) + ) + .withClosedLoopRamps( + new ClosedLoopRampsConfigs() + .withTorqueClosedLoopRampPeriod(PivotConstants.PIVOT_RAMP_RATE) + ) + .withCurrentLimits( + new CurrentLimitsConfigs() + .withStatorCurrentLimit(PivotConstants.PIVOT_CURRENT_LIMIT) + ) + .withFeedback( + new FeedbackConfigs() + .withRotorToSensorRatio(PivotConstants.ROTOR_TO_SENSOR_RATIO) + ) + .withSoftwareLimitSwitch( + new SoftwareLimitSwitchConfigs() + .withForwardSoftLimitEnable(true) + .withForwardSoftLimitThreshold(PivotConstants.PIVOT_MAX_POS) + .withReverseSoftLimitEnable(true) + .withReverseSoftLimitThreshold(PivotConstants.PIVOT_MIN_POS) + ); + + + public PivotSubsystem(int canId, String canBusName){ + pivotMotor = new LoggedTalon(canId, canBusName, pivotConfig); + pivotMotor.setPosition(PivotConstants.PIVOT_INIT_POS); + } + + @Override + public void periodic(){ + pivotMotor.logStats(); + if(DebugConstants.MASTER_DEBUG || DebugConstants.PIVOT_DEBUG){ + pivotMotor.publishStats(); + } + } + + public void setPositionReference(double position){ + pivotMotor.setPositionReference(position); + } + + public double getClosedLoopError(){ + return pivotMotor.getClosedLoopError(); + } +} diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java new file mode 100644 index 00000000..f0167ae2 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -0,0 +1,59 @@ +package frc.robot.subsystems.Intake.Roller; + +import static frc.robot.Constants.DebugConstants.MASTER_DEBUG; +import static frc.robot.Constants.DebugConstants.ROLLER_DEBUG; + +import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; + +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.util.LoggedTalon; + +public class RollerSubsystem extends SubsystemBase{ + private LoggedTalon rollerMotor; + + private TalonFXConfiguration rollerConfig = new TalonFXConfiguration() + .withSlot0( + new Slot0Configs() + .withKP(RollerConstants.ROLLER_KP) + .withKI(RollerConstants.ROLLER_KI) + .withKD(RollerConstants.ROLLER_KD) + .withKS(RollerConstants.ROLLER_KS) + .withKV(RollerConstants.ROLLER_KV) + ) + .withClosedLoopRamps( + new ClosedLoopRampsConfigs() + .withTorqueClosedLoopRampPeriod(RollerConstants.ROLLER_RAMP_RATE) + ) + .withCurrentLimits( + new CurrentLimitsConfigs() + .withStatorCurrentLimit(RollerConstants.ROLLER_CURRENT_LIMIT) + ); + + public RollerSubsystem(int canId, String canBusName){ + rollerMotor = new LoggedTalon(canId, canBusName, rollerConfig); + } + + @Override + public void periodic(){ + rollerMotor.logStats(); + if(MASTER_DEBUG || ROLLER_DEBUG){ + rollerMotor.publishStats(); + } + rollerMotor.logStats(); + } + /** + * Set the speed of the roller motor + * @param speed target speed in RPS + */ + public void setRollerSpeed(double speed){ + rollerMotor.setVelocityReference(speed); + } + + public double getClosedLoopError(){ + return rollerMotor.getClosedLoopError(); + } +} From 386856c4b03e2db1a50af750ec805d13320295ce Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 12:36:17 -0800 Subject: [PATCH 09/60] Remove the second log call in periodic --- .../java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index f0167ae2..8325c4d6 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -43,7 +43,6 @@ public void periodic(){ if(MASTER_DEBUG || ROLLER_DEBUG){ rollerMotor.publishStats(); } - rollerMotor.logStats(); } /** * Set the speed of the roller motor From 11b7284c1e44ceb1fa59dd56057392366a0d5cef Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 16:31:33 -0800 Subject: [PATCH 10/60] Make pivot ready to test --- ...lerOnCommand.java => RollerInCommand.java} | 6 +-- .../Intake/Roller/RollerOutCommand.java | 26 +++++++++++++ .../Intake/Roller/RollerStopCommand.java | 26 +++++++++++++ src/main/java/frc/robot/Constants.java | 5 ++- src/main/java/frc/robot/RobotContainer.java | 38 ++++++++++++++++++- .../Intake/Pivot/PivotSubsystem.java | 10 ++++- .../Intake/Roller/RollerSubsystem.java | 6 ++- 7 files changed, 108 insertions(+), 9 deletions(-) rename src/main/java/frc/robot/Commands/Intake/Roller/{RollerOnCommand.java => RollerInCommand.java} (77%) create mode 100644 src/main/java/frc/robot/Commands/Intake/Roller/RollerOutCommand.java create mode 100644 src/main/java/frc/robot/Commands/Intake/Roller/RollerStopCommand.java diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java similarity index 77% rename from src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java rename to src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java index c15b198b..255aa7e0 100644 --- a/src/main/java/frc/robot/Commands/Intake/Roller/RollerOnCommand.java +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java @@ -4,18 +4,18 @@ import frc.robot.Constants.IntakeConstans.RollerConstants; import frc.robot.subsystems.Intake.Roller.RollerSubsystem; -public class RollerOnCommand extends Command{ +public class RollerInCommand extends Command{ private final RollerSubsystem rollerSubsystem; - public RollerOnCommand(RollerSubsystem rollerSubsystem){ + public RollerInCommand(RollerSubsystem rollerSubsystem){ this.rollerSubsystem = rollerSubsystem; this.addRequirements(rollerSubsystem); } @Override public void initialize(){ - rollerSubsystem.setRollerSpeed(RollerConstants.ROLLER_ON_SPEED); + rollerSubsystem.setRollerSpeed(RollerConstants.ROLLER_IN_SPEED); } @Override diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerOutCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerOutCommand.java new file mode 100644 index 00000000..a0ffe6e6 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerOutCommand.java @@ -0,0 +1,26 @@ +package frc.robot.Commands.Intake.Roller; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.subsystems.Intake.Roller.RollerSubsystem; + +public class RollerOutCommand extends Command{ + + private final RollerSubsystem rollerSubsystem; + + public RollerOutCommand(RollerSubsystem rollerSubsystem){ + this.rollerSubsystem = rollerSubsystem; + this.addRequirements(rollerSubsystem); + } + + @Override + public void initialize(){ + rollerSubsystem.setRollerSpeed(RollerConstants.ROLLER_OUT_SPEED); + } + + @Override + public boolean isFinished(){ + return Math.abs(rollerSubsystem.getClosedLoopError()) + < RollerConstants.ROLLER_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerStopCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerStopCommand.java new file mode 100644 index 00000000..4948c65b --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerStopCommand.java @@ -0,0 +1,26 @@ +package frc.robot.Commands.Intake.Roller; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.subsystems.Intake.Roller.RollerSubsystem; + +public class RollerStopCommand extends Command{ + + private final RollerSubsystem rollerSubsystem; + + public RollerStopCommand(RollerSubsystem rollerSubsystem){ + this.rollerSubsystem = rollerSubsystem; + this.addRequirements(rollerSubsystem); + } + + @Override + public void initialize(){ + rollerSubsystem.setRollerSpeed(RollerConstants.ROLLER_OFF_SPEED); + } + + @Override + public boolean isFinished(){ + return Math.abs(rollerSubsystem.getClosedLoopError()) + < RollerConstants.ROLLER_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 3582a2c8..2fd4e22d 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -31,6 +31,7 @@ public static class IntakeConstans{ public static class PivotConstants{ public static final int PIVOT_CAN_ID = 1; + public static final String PIVOT_CAN_NAME = "can"; public static final double PIVOT_KP = 0.; public static final double PIVOT_KI = 0.; @@ -53,6 +54,7 @@ public static class PivotConstants{ public static class RollerConstants{ public static final int ROLLER_CAN_ID = 0; + public static final String ROLLER_CAN_NAME = "can"; public static final double ROLLER_SPEED = 0.5; public static final double ROLLER_KP = 0; public static final double ROLLER_KI = 0; @@ -60,7 +62,8 @@ public static class RollerConstants{ public static final double ROLLER_KS = 0; public static final double ROLLER_KV = 0; - public static final double ROLLER_ON_SPEED = 0.5; + public static final double ROLLER_IN_SPEED = 0.5; + public static final double ROLLER_OUT_SPEED = -0.5; public static final double ROLLER_OFF_SPEED = 0; public static final double ROLLER_TOLERANCE = 0.1; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 58f27688..db17ae39 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -12,10 +12,17 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.RunCommand; +import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; +import frc.robot.subsystems.Intake.Roller.RollerSubsystem; import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; +import frc.robot.Commands.Intake.Pivot.PivotToSourceCommand; +import frc.robot.Commands.Intake.Roller.RollerInCommand; +import frc.robot.Commands.Intake.Roller.RollerOutCommand; +import frc.robot.Commands.Intake.Roller.RollerStopCommand; import frc.robot.Constants.VisionConstants; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -26,6 +33,10 @@ public class RobotContainer { private PS5DriveController driveController; + private CommandPS5Controller mechController; + + private final PivotSubsystem pivotSubsystem = new PivotSubsystem(); + private final RollerSubsystem rollerSubsystem = new RollerSubsystem(); private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); private final VisionSubsystem visionSubsystem2 = new VisionSubsystem( @@ -41,6 +52,7 @@ public class RobotContainer { /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); + constructMechController(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -95,10 +107,34 @@ public Command getAutonomousCommand() { * 0 */ private void constructDriveController(){ - driveController = new PS5DriveController(); + DriverStation.refreshData(); + // if(DriverStation.getJoystickName(0).equals("Controller (Xbox One For Windows)")) { + // driveController = new XboxDriveController(); + // } + // else if(DriverStation.getJoystickName(0).equals("DualSense Wireless Controller")){ + driveController = new PS5DriveController(); + // } + // else{ + // driveController = new DualJoystickDriveController(); + // } driveController.setDeadZone(0.05); } + private void constructMechController(){ + mechController = new CommandPS5Controller(1); + pivotSubsystem.setDefaultCommand( + new RunCommand(() -> { + pivotSubsystem.setVelocityReference(mechController.getLeftY()); + }, + pivotSubsystem + ) + ); + mechController.triangle().onTrue(new RollerOutCommand(rollerSubsystem)); + mechController.circle().onTrue(new RollerInCommand(rollerSubsystem)); + mechController.square().onTrue(new RollerStopCommand(rollerSubsystem)); + mechController.cross().onTrue(new PivotToSourceCommand(pivotSubsystem)); + } + /** * Starts datalog at /u/logs */ diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index e85c03a9..cf09b489 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -53,8 +53,10 @@ public class PivotSubsystem extends SubsystemBase{ ); - public PivotSubsystem(int canId, String canBusName){ - pivotMotor = new LoggedTalon(canId, canBusName, pivotConfig); + public PivotSubsystem(){ + pivotMotor = new LoggedTalon( + PivotConstants.PIVOT_CAN_ID, PivotConstants.PIVOT_CAN_NAME, pivotConfig + ); pivotMotor.setPosition(PivotConstants.PIVOT_INIT_POS); } @@ -70,6 +72,10 @@ public void setPositionReference(double position){ pivotMotor.setPositionReference(position); } + public void setVelocityReference(double velocity){ + pivotMotor.setVelocityReference(velocity); + } + public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index 8325c4d6..65e416fa 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -33,8 +33,10 @@ public class RollerSubsystem extends SubsystemBase{ .withStatorCurrentLimit(RollerConstants.ROLLER_CURRENT_LIMIT) ); - public RollerSubsystem(int canId, String canBusName){ - rollerMotor = new LoggedTalon(canId, canBusName, rollerConfig); + public RollerSubsystem(){ + rollerMotor = new LoggedTalon( + RollerConstants.ROLLER_CAN_ID, RollerConstants.ROLLER_CAN_NAME, rollerConfig + ); } @Override From 6e3b73382d6744178d6d1f1b9f7f1ba90d3a69a6 Mon Sep 17 00:00:00 2001 From: Jesse Date: Mon, 24 Feb 2025 19:05:47 -0800 Subject: [PATCH 11/60] Add methods to allow voltage requests to account for motor not under canivore --- src/main/java/frc/robot/util/LoggedTalon.java | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index a509f818..59317653 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -6,7 +6,9 @@ import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; +import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; import edu.wpi.first.networktables.DoublePublisher; @@ -86,6 +88,15 @@ public void setPositionReference(double position){ motor.setControl(new PositionTorqueCurrentFOC(position)); } + /** + * Sets the motor's position reference with voltage + * @param position position reference + */ + public void setPositionReferenceWithVoltage(double position){ + targetPosition = position; + motor.setControl(new PositionVoltage(position)); + } + /** * Sets the motor's position reference with feedforward * @param position position reference @@ -97,6 +108,7 @@ public void setPositionReferenceWithArbFF(double position, double arbFF){ new PositionTorqueCurrentFOC(position).withFeedForward(arbFF) ); } + /** * Set the motor's velocity reference * @param velocity velocity reference @@ -105,6 +117,14 @@ public void setVelocityReference(double velocity){ targetVelocity = velocity; motor.setControl(new VelocityTorqueCurrentFOC(velocity)); } + /** + * Sets the motor's velocity reference with voltage + * @param velocity velocity reference + */ + public void setVelocityReferenceWithVoltage(double velocity){ + targetVelocity = velocity; + motor.setControl(new VelocityVoltage(velocity)); + } /** * Sets the motor's position to a certain value From 9c5123f40378e645003288e1e75313658d9d2f11 Mon Sep 17 00:00:00 2001 From: Jesse Date: Mon, 24 Feb 2025 19:07:24 -0800 Subject: [PATCH 12/60] Using voltage requests instead of torque current FOC requests to account for motor not under canivore --- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 4 ++-- .../frc/robot/subsystems/Intake/Roller/RollerSubsystem.java | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index cf09b489..2066aaf4 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -69,11 +69,11 @@ public void periodic(){ } public void setPositionReference(double position){ - pivotMotor.setPositionReference(position); + pivotMotor.setPositionReferenceWithVoltage(position); } public void setVelocityReference(double velocity){ - pivotMotor.setVelocityReference(velocity); + pivotMotor.setVelocityReferenceWithVoltage(velocity); } public double getClosedLoopError(){ diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index 65e416fa..9d98ab92 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -46,12 +46,13 @@ public void periodic(){ rollerMotor.publishStats(); } } + /** * Set the speed of the roller motor * @param speed target speed in RPS */ public void setRollerSpeed(double speed){ - rollerMotor.setVelocityReference(speed); + rollerMotor.setVelocityReferenceWithVoltage(speed); } public double getClosedLoopError(){ From 5789cf4f244798b71c9065b415ac4fe24e2ca89f Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 25 Feb 2025 14:21:01 -0800 Subject: [PATCH 13/60] Added more intake commands to test and bind them in a seperate method --- .../Intake/Pivot/PivotToOuttakeCommand.java | 25 +++++++++++++++++++ .../Intake/Pivot/PivotUp90Command.java | 25 +++++++++++++++++++ src/main/java/frc/robot/Constants.java | 11 +++++--- src/main/java/frc/robot/RobotContainer.java | 23 ++++++++++++++--- 4 files changed, 76 insertions(+), 8 deletions(-) create mode 100644 src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java create mode 100644 src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java new file mode 100644 index 00000000..487e5b8a --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Intake.Pivot; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; + +public class PivotToOuttakeCommand extends Command{ + private final PivotSubsystem pivotSubsystem; + + public PivotToOuttakeCommand(PivotSubsystem pivotSubsystem){ + this.pivotSubsystem = pivotSubsystem; + this.addRequirements(pivotSubsystem); + } + + @Override + public void initialize(){ + pivotSubsystem.setPositionReference(PivotConstants.OUTTAKE_POS); + } + + @Override + public boolean isFinished(){ + return Math.abs(pivotSubsystem.getClosedLoopError()) + < PivotConstants.PIVOT_TOLERANCE; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java new file mode 100644 index 00000000..6bb85676 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Intake.Pivot; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; + +public class PivotUp90Command extends Command{ + private final PivotSubsystem pivotSubsystem; + + public PivotUp90Command(PivotSubsystem pivotSubsystem){ + this.pivotSubsystem = pivotSubsystem; + this.addRequirements(pivotSubsystem); + } + + @Override + public void initialize(){ + pivotSubsystem.setPositionReference(PivotConstants.PIVOT_MAX_POS); + } + + @Override + public boolean isFinished(){ + return Math.abs(pivotSubsystem.getClosedLoopError()) + < PivotConstants.PIVOT_TOLERANCE; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 2fd4e22d..c6a37c37 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -39,14 +39,17 @@ public static class PivotConstants{ public static final double PIVOT_KG = 0.; public static final double PIVOT_KV = 0.; + public static final double PIVOT_MANUAL_SPEED = 0.15; + public static final double SOURCE_POS = 0.; + public static final double OUTTAKE_POS = -0.15; public static final double PIVOT_TOLERANCE = 0.1; - public static final double ROTOR_TO_SENSOR_RATIO = 0.; - public static final double PIVOT_INIT_POS = 90.; - public static final double PIVOT_MAX_POS = 90.; - public static final double PIVOT_MIN_POS = -90.; + public static final double ROTOR_TO_SENSOR_RATIO = 20.; + public static final double PIVOT_INIT_POS = 0.25; + public static final double PIVOT_MAX_POS = 0.25; + public static final double PIVOT_MIN_POS = -0.25; public static final double PIVOT_RAMP_RATE = 0.02; public static final double PIVOT_CURRENT_LIMIT = 100.; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index db17ae39..4d98a32e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -19,7 +19,9 @@ import frc.robot.subsystems.Intake.Roller.RollerSubsystem; import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; +import frc.robot.Commands.Intake.Pivot.PivotToOuttakeCommand; import frc.robot.Commands.Intake.Pivot.PivotToSourceCommand; +import frc.robot.Commands.Intake.Pivot.PivotUp90Command; import frc.robot.Commands.Intake.Roller.RollerInCommand; import frc.robot.Commands.Intake.Roller.RollerOutCommand; import frc.robot.Commands.Intake.Roller.RollerStopCommand; @@ -53,6 +55,7 @@ public class RobotContainer { public RobotContainer() { constructDriveController(); constructMechController(); + bindIntake(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -120,8 +123,17 @@ private void constructDriveController(){ driveController.setDeadZone(0.05); } + /** + * Constructs the mech controller at port 1 + */ private void constructMechController(){ mechController = new CommandPS5Controller(1); + } + + /** + * Binds the intake commands to the mech controller + */ + private void bindIntake(){ pivotSubsystem.setDefaultCommand( new RunCommand(() -> { pivotSubsystem.setVelocityReference(mechController.getLeftY()); @@ -129,10 +141,13 @@ private void constructMechController(){ pivotSubsystem ) ); - mechController.triangle().onTrue(new RollerOutCommand(rollerSubsystem)); - mechController.circle().onTrue(new RollerInCommand(rollerSubsystem)); - mechController.square().onTrue(new RollerStopCommand(rollerSubsystem)); - mechController.cross().onTrue(new PivotToSourceCommand(pivotSubsystem)); + mechController.L2().onTrue(new RollerOutCommand(rollerSubsystem)); + mechController.L2().toggleOnFalse(new RollerStopCommand(rollerSubsystem)); + mechController.R2().onTrue(new RollerInCommand(rollerSubsystem)); + mechController.R2().toggleOnFalse(new RollerStopCommand(rollerSubsystem)); + mechController.povDown().onTrue(new PivotToOuttakeCommand(pivotSubsystem)); + mechController.povUp().onTrue(new PivotToSourceCommand(pivotSubsystem)); + mechController.L1().onTrue(new PivotUp90Command(pivotSubsystem)); } /** From 795c922271fdcb0718ef8269d695ac2874235b0a Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 18 Feb 2025 17:40:22 -0800 Subject: [PATCH 14/60] Force the drive controller to be PS5 controller --- src/main/java/frc/robot/RobotContainer.java | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 4d98a32e..3723b807 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -110,16 +110,7 @@ public Command getAutonomousCommand() { * 0 */ private void constructDriveController(){ - DriverStation.refreshData(); - // if(DriverStation.getJoystickName(0).equals("Controller (Xbox One For Windows)")) { - // driveController = new XboxDriveController(); - // } - // else if(DriverStation.getJoystickName(0).equals("DualSense Wireless Controller")){ - driveController = new PS5DriveController(); - // } - // else{ - // driveController = new DualJoystickDriveController(); - // } + driveController = new PS5DriveController(); driveController.setDeadZone(0.05); } From fd6639fda95582716b9c114cba01669405b52825 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 16:31:33 -0800 Subject: [PATCH 15/60] Make pivot ready to test --- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 2066aaf4..f358032d 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -76,6 +76,10 @@ public void setVelocityReference(double velocity){ pivotMotor.setVelocityReferenceWithVoltage(velocity); } + public void setVelocityReference(double velocity){ + pivotMotor.setVelocityReference(velocity); + } + public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } From be5c04cbf597c0ee68e9794da0b8596cdc47f953 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 16:31:33 -0800 Subject: [PATCH 16/60] Make pivot ready to test --- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index f358032d..59bebf70 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -72,7 +72,7 @@ public void setPositionReference(double position){ pivotMotor.setPositionReferenceWithVoltage(position); } - public void setVelocityReference(double velocity){ + public void setVelocityReferenceWithVoltage(double velocity){ pivotMotor.setVelocityReferenceWithVoltage(velocity); } @@ -80,6 +80,10 @@ public void setVelocityReference(double velocity){ pivotMotor.setVelocityReference(velocity); } + public void setVelocityReference(double velocity){ + pivotMotor.setVelocityReference(velocity); + } + public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } From 2c3b4fcac7cc0e2ee7e7de09ae87fa0738592fe8 Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 25 Feb 2025 14:37:19 -0800 Subject: [PATCH 17/60] Onlyuse mech controller joystick to control pivot when its reading is greater than deadzone --- src/main/java/frc/robot/RobotContainer.java | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3723b807..900859e2 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -131,6 +131,7 @@ private void bindIntake(){ }, pivotSubsystem ) + .onlyWhile(() -> Math.abs(mechController.getLeftY()) > 0.05) ); mechController.L2().onTrue(new RollerOutCommand(rollerSubsystem)); mechController.L2().toggleOnFalse(new RollerStopCommand(rollerSubsystem)); From 99e3c78250758f1ecccfe25469902c926f086371 Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 25 Feb 2025 14:42:02 -0800 Subject: [PATCH 18/60] Change set reference methods to set reference with velocity requests --- .../robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java | 2 +- .../robot/Commands/Intake/Pivot/PivotToSourceCommand.java | 2 +- .../frc/robot/Commands/Intake/Pivot/PivotUp90Command.java | 2 +- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 6 +----- 4 files changed, 4 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java index 487e5b8a..72057715 100644 --- a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToOuttakeCommand.java @@ -14,7 +14,7 @@ public PivotToOuttakeCommand(PivotSubsystem pivotSubsystem){ @Override public void initialize(){ - pivotSubsystem.setPositionReference(PivotConstants.OUTTAKE_POS); + pivotSubsystem.setPositionReferenceWithVoltage(PivotConstants.OUTTAKE_POS); } @Override diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java index 8ce33956..e11a571e 100644 --- a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToSourceCommand.java @@ -14,7 +14,7 @@ public PivotToSourceCommand(PivotSubsystem pivotSubsystem){ @Override public void initialize(){ - pivotSubsystem.setPositionReference(PivotConstants.SOURCE_POS); + pivotSubsystem.setPositionReferenceWithVoltage(PivotConstants.SOURCE_POS); } @Override diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java index 6bb85676..6db72921 100644 --- a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotUp90Command.java @@ -14,7 +14,7 @@ public PivotUp90Command(PivotSubsystem pivotSubsystem){ @Override public void initialize(){ - pivotSubsystem.setPositionReference(PivotConstants.PIVOT_MAX_POS); + pivotSubsystem.setPositionReferenceWithVoltage(PivotConstants.PIVOT_MAX_POS); } @Override diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 59bebf70..fedbb823 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -68,7 +68,7 @@ public void periodic(){ } } - public void setPositionReference(double position){ + public void setPositionReferenceWithVoltage(double position){ pivotMotor.setPositionReferenceWithVoltage(position); } @@ -80,10 +80,6 @@ public void setVelocityReference(double velocity){ pivotMotor.setVelocityReference(velocity); } - public void setVelocityReference(double velocity){ - pivotMotor.setVelocityReference(velocity); - } - public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } From b612863064ff84b5e900de4b849d71df949bd9f3 Mon Sep 17 00:00:00 2001 From: swaswa999 Date: Tue, 25 Feb 2025 21:50:46 -0800 Subject: [PATCH 19/60] setPositionReference --- src/main/java/frc/robot/Constants.java | 1 + .../Intake/Pivot/PivotSubsystem.java | 24 +++++++++++++++++++ 2 files changed, 25 insertions(+) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c6a37c37..1b5d546f 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -38,6 +38,7 @@ public static class PivotConstants{ public static final double PIVOT_KD = 0.; public static final double PIVOT_KG = 0.; public static final double PIVOT_KV = 0.; + public static final double PIVOT_KS = 0.; public static final double PIVOT_MANUAL_SPEED = 0.15; diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index fedbb823..7c87e3c4 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -9,6 +9,7 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.signals.GravityTypeValue; +import edu.wpi.first.math.controller.ArmFeedforward; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.DebugConstants; import frc.robot.Constants.IntakeConstans.PivotConstants; @@ -17,6 +18,13 @@ public class PivotSubsystem extends SubsystemBase{ private LoggedTalon pivotMotor; + private double arbFF; + + ArmFeedforward feedforward = new ArmFeedforward( + PivotConstants.PIVOT_KS, + PivotConstants.PIVOT_KG, + PivotConstants.PIVOT_KV); + private TalonFXConfiguration pivotConfig = new TalonFXConfiguration() .withSlot0( @@ -72,6 +80,22 @@ public void setPositionReferenceWithVoltage(double position){ pivotMotor.setPositionReferenceWithVoltage(position); } + /** + * Sets the elevator to a specific position. + * @param positionReference target position + */ + public void setPositionReference(double positionReference){ + if (positionReference > pivotMotor.getPosition()) { + + double angleRad = Math.toRadians(pivotMotor.getPosition()); + arbFF = feedforward.calculate(angleRad, 0.0); + } + else { + arbFF = 0; + } + pivotMotor.setPositionReferenceWithArbFF(positionReference, arbFF); + } + public void setVelocityReferenceWithVoltage(double velocity){ pivotMotor.setVelocityReferenceWithVoltage(velocity); } From 494e1fff6e41b3fb6905f125b17cb82951da604c Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Wed, 26 Feb 2025 11:45:57 -0800 Subject: [PATCH 20/60] intake tested and tuned --- src/main/java/frc/robot/Constants.java | 8 ++++---- src/main/java/frc/robot/RobotContainer.java | 17 +++++++++++++---- .../Intake/Roller/RollerSubsystem.java | 16 +++++++++++++++- src/main/java/frc/robot/util/LoggedTalon.java | 4 ++++ 4 files changed, 36 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 1b5d546f..eba24ba8 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -30,8 +30,8 @@ public static class OperatorConstants { public static class IntakeConstans{ public static class PivotConstants{ - public static final int PIVOT_CAN_ID = 1; - public static final String PIVOT_CAN_NAME = "can"; + public static final int PIVOT_CAN_ID = 14; + public static final String PIVOT_CAN_NAME = "rio"; public static final double PIVOT_KP = 0.; public static final double PIVOT_KI = 0.; @@ -57,8 +57,8 @@ public static class PivotConstants{ } public static class RollerConstants{ - public static final int ROLLER_CAN_ID = 0; - public static final String ROLLER_CAN_NAME = "can"; + public static final int ROLLER_CAN_ID = 16; + public static final String ROLLER_CAN_NAME = "rio"; public static final double ROLLER_SPEED = 0.5; public static final double ROLLER_KP = 0; public static final double ROLLER_KI = 0; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 900859e2..a0fcc068 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -11,6 +11,8 @@ import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.ConditionalCommand; +import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -133,10 +135,17 @@ private void bindIntake(){ ) .onlyWhile(() -> Math.abs(mechController.getLeftY()) > 0.05) ); - mechController.L2().onTrue(new RollerOutCommand(rollerSubsystem)); - mechController.L2().toggleOnFalse(new RollerStopCommand(rollerSubsystem)); - mechController.R2().onTrue(new RollerInCommand(rollerSubsystem)); - mechController.R2().toggleOnFalse(new RollerStopCommand(rollerSubsystem)); + + rollerSubsystem.setDefaultCommand(new ConditionalCommand( + new InstantCommand( () -> { + //ps5 trigger's range is -1 to 1, with non-input position being -1. This maps the range -1 to 1 to 0 to 1. + rollerSubsystem.setRollerSpeed(.25 * (mechController.getL2Axis() + 1.) / 2.); + }, rollerSubsystem), + new InstantCommand( () -> { + rollerSubsystem.setRollerSpeed(.15 * (mechController.getL2Axis() - mechController.getR2Axis())); + }, rollerSubsystem), + () -> rollerSubsystem.getIntakeSensor())); + mechController.povDown().onTrue(new PivotToOuttakeCommand(pivotSubsystem)); mechController.povUp().onTrue(new PivotToSourceCommand(pivotSubsystem)); mechController.L1().onTrue(new PivotUp90Command(pivotSubsystem)); diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index 9d98ab92..0e7c3062 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -5,15 +5,19 @@ import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.InvertedValue; +import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.IntakeConstans.RollerConstants; import frc.robot.util.LoggedTalon; public class RollerSubsystem extends SubsystemBase{ private LoggedTalon rollerMotor; + private DigitalInput intakeSensor; private TalonFXConfiguration rollerConfig = new TalonFXConfiguration() .withSlot0( @@ -24,6 +28,10 @@ public class RollerSubsystem extends SubsystemBase{ .withKS(RollerConstants.ROLLER_KS) .withKV(RollerConstants.ROLLER_KV) ) + .withMotorOutput( + new MotorOutputConfigs() + .withInverted(InvertedValue.Clockwise_Positive) + ) .withClosedLoopRamps( new ClosedLoopRampsConfigs() .withTorqueClosedLoopRampPeriod(RollerConstants.ROLLER_RAMP_RATE) @@ -37,6 +45,7 @@ public RollerSubsystem(){ rollerMotor = new LoggedTalon( RollerConstants.ROLLER_CAN_ID, RollerConstants.ROLLER_CAN_NAME, rollerConfig ); + intakeSensor = new DigitalInput(1); } @Override @@ -45,6 +54,11 @@ public void periodic(){ if(MASTER_DEBUG || ROLLER_DEBUG){ rollerMotor.publishStats(); } + System.out.println(!intakeSensor.get()); + } + + public boolean getIntakeSensor() { + return !intakeSensor.get(); } /** @@ -52,7 +66,7 @@ public void periodic(){ * @param speed target speed in RPS */ public void setRollerSpeed(double speed){ - rollerMotor.setVelocityReferenceWithVoltage(speed); + rollerMotor.setSpeed(speed); } public double getClosedLoopError(){ diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index 59317653..20e1890b 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -88,6 +88,10 @@ public void setPositionReference(double position){ motor.setControl(new PositionTorqueCurrentFOC(position)); } + public void setSpeed(double speed) { + motor.set(speed); + } + /** * Sets the motor's position reference with voltage * @param position position reference From 008434b5a3dc0b302b11142c4b5780faaecb5704 Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Wed, 26 Feb 2025 12:21:12 -0800 Subject: [PATCH 21/60] working conversion factor for pivot --- src/main/java/frc/robot/Constants.java | 12 ++++++------ .../subsystems/Intake/Pivot/PivotSubsystem.java | 11 ++++++----- .../subsystems/Intake/Roller/RollerSubsystem.java | 1 - 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index eba24ba8..6286ecb2 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -42,15 +42,15 @@ public static class PivotConstants{ public static final double PIVOT_MANUAL_SPEED = 0.15; - public static final double SOURCE_POS = 0.; - public static final double OUTTAKE_POS = -0.15; + public static final double SOURCE_POS = Units.degreesToRadians(50); + public static final double OUTTAKE_POS = Units.degreesToRadians(-45); public static final double PIVOT_TOLERANCE = 0.1; - public static final double ROTOR_TO_SENSOR_RATIO = 20.; - public static final double PIVOT_INIT_POS = 0.25; - public static final double PIVOT_MAX_POS = 0.25; - public static final double PIVOT_MIN_POS = -0.25; + public static final double ROTOR_TO_SENSOR_RATIO = 20. / (2. * Math.PI); + public static final double PIVOT_INIT_POS = Units.degreesToRadians(94); + public static final double PIVOT_MAX_POS = Units.degreesToRadians(94); + public static final double PIVOT_MIN_POS = Units.degreesToRadians(-45); public static final double PIVOT_RAMP_RATE = 0.02; public static final double PIVOT_CURRENT_LIMIT = 100.; diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 7c87e3c4..125870c9 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -10,6 +10,7 @@ import com.ctre.phoenix6.signals.GravityTypeValue; import edu.wpi.first.math.controller.ArmFeedforward; +import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.DebugConstants; import frc.robot.Constants.IntakeConstans.PivotConstants; @@ -50,7 +51,8 @@ public class PivotSubsystem extends SubsystemBase{ ) .withFeedback( new FeedbackConfigs() - .withRotorToSensorRatio(PivotConstants.ROTOR_TO_SENSOR_RATIO) + // .withRotorToSensorRatio(PivotConstants.ROTOR_TO_SENSOR_RATIO) + .withSensorToMechanismRatio(PivotConstants.ROTOR_TO_SENSOR_RATIO) ) .withSoftwareLimitSwitch( new SoftwareLimitSwitchConfigs() @@ -74,6 +76,7 @@ public void periodic(){ if(DebugConstants.MASTER_DEBUG || DebugConstants.PIVOT_DEBUG){ pivotMotor.publishStats(); } + System.out.println(Units.radiansToDegrees(pivotMotor.getPosition())); } public void setPositionReferenceWithVoltage(double position){ @@ -86,12 +89,10 @@ public void setPositionReferenceWithVoltage(double position){ */ public void setPositionReference(double positionReference){ if (positionReference > pivotMotor.getPosition()) { - - double angleRad = Math.toRadians(pivotMotor.getPosition()); - arbFF = feedforward.calculate(angleRad, 0.0); + arbFF = feedforward.calculate(positionReference, 0.0); } else { - arbFF = 0; + arbFF = 0; } pivotMotor.setPositionReferenceWithArbFF(positionReference, arbFF); } diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index 0e7c3062..e04e4ff0 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -54,7 +54,6 @@ public void periodic(){ if(MASTER_DEBUG || ROLLER_DEBUG){ rollerMotor.publishStats(); } - System.out.println(!intakeSensor.get()); } public boolean getIntakeSensor() { From d2721668aeca927b07f616c120037a0b185e7e6b Mon Sep 17 00:00:00 2001 From: Jesse Date: Wed, 26 Feb 2025 15:16:11 -0800 Subject: [PATCH 22/60] Allow setting current and duty cycle requests --- src/main/java/frc/robot/util/LoggedTalon.java | 44 +++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index 20e1890b..ed399128 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -2,11 +2,15 @@ import java.util.EnumSet; +import javax.xml.crypto.Data; + import com.ctre.phoenix6.StatusCode; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.DutyCycleOut; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.controls.TorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; @@ -37,6 +41,8 @@ public class LoggedTalon{ private DoublePublisher temperaturePublisher; private DoublePublisher targetPositionPublisher; private DoublePublisher targetVelocityPublisher; + private DoublePublisher targetTorqueCurrentFOCPublisher; + private DoublePublisher targetDutyCyclePublisher; private DoublePublisher closedLoopErrorPublisher; private DoubleLogEntry positionLogEntry; @@ -47,10 +53,14 @@ public class LoggedTalon{ private DoubleLogEntry temperatureLogEntry; private DoubleLogEntry targetPositionLogEntry; private DoubleLogEntry targetVelocityLogEntry; + private DoubleLogEntry targetTorqueCurrentFOCLogEntry; + private DoubleLogEntry targetDutyCycleLogEntry; private DoubleLogEntry closedLoopErrorLogEntry; private double targetPosition; private double targetVelocity; + private double targetTorqueCurrentFOC; + private double targetDutyCycle; public LoggedTalon( int canId, String canBusName, TalonFXConfiguration talonConfig @@ -130,6 +140,24 @@ public void setVelocityReferenceWithVoltage(double velocity){ motor.setControl(new VelocityVoltage(velocity)); } + /** + * Set the current of the motor directly + * @param current target current output + */ + public void setTorqueCurrentFOC(double current){ + targetTorqueCurrentFOC = current; + motor.setControl(new TorqueCurrentFOC(current)); + } + + /** + * Set duty cycle output + * @param output duty cycle output from -1.0 to 1.0 + */ + public void setDutyCycle(double output){ + targetDutyCycle = output; + motor.setControl(new DutyCycleOut(output)); + } + /** * Sets the motor's position to a certain value * @param position mechanisam position after taking the position conversion @@ -203,6 +231,14 @@ private void initNT(int canId){ canId + "targetVelocity" ).publish(); + targetTorqueCurrentFOCPublisher = motorStatsTable.getDoubleTopic( + canId + "targetTorqueCurrentFOC" + ).publish(); + + targetDutyCyclePublisher = motorStatsTable.getDoubleTopic( + canId + "targetDutyCycle" + ).publish(); + closedLoopErrorPublisher = motorStatsTable.getDoubleTopic( canId + "closedLoopError" ).publish(); @@ -244,6 +280,14 @@ private void initLogs(int canId){ targetVelocityLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "targetVelocity" ); + + targetTorqueCurrentFOCLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetTorqueCurrentFOC" + ); + + targetDutyCycleLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetDutyCycle" + ); closedLoopErrorLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "closedLoopError" From e50558aba4eeecd8a3851ed45a4e4f82db188d12 Mon Sep 17 00:00:00 2001 From: Jesse Date: Wed, 26 Feb 2025 11:40:06 -0800 Subject: [PATCH 23/60] Added logged boolean sensor --- src/main/java/frc/robot/Constants.java | 1 + .../frc/robot/util/LoggedBooleanSensor.java | 68 +++++++++++++++++++ 2 files changed, 69 insertions(+) create mode 100644 src/main/java/frc/robot/util/LoggedBooleanSensor.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 6286ecb2..c7f9a4fa 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -131,6 +131,7 @@ public static class SwerveConstants { public static class LoggingConstants{ public static final String SWERVE_TABLE = "SwerveStats"; + public static final String SENSOR_TABLE = "Sensors"; } public static class DebugConstants{ diff --git a/src/main/java/frc/robot/util/LoggedBooleanSensor.java b/src/main/java/frc/robot/util/LoggedBooleanSensor.java new file mode 100644 index 00000000..f0f1fd5c --- /dev/null +++ b/src/main/java/frc/robot/util/LoggedBooleanSensor.java @@ -0,0 +1,68 @@ +package frc.robot.util; + +import edu.wpi.first.networktables.BooleanPublisher; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.util.datalog.BooleanLogEntry; +import edu.wpi.first.wpilibj.DataLogManager; +import edu.wpi.first.wpilibj.DigitalInput; +import frc.robot.Constants.LoggingConstants; + +public class LoggedBooleanSensor { + + private final DigitalInput sensor; + + private NetworkTableInstance ntInstance; + private NetworkTable sensorStatsTable; + private BooleanPublisher sensorReadingPublisher; + + private BooleanLogEntry sensorReadingLogEntry; + + public LoggedBooleanSensor(String name, int port){ + sensor = new DigitalInput(port); + initNT(name); + initLogs(name); + } + + /** + * Get the reading of the sensor + * @return + */ + public boolean get(){ + return sensor.get(); + } + + /** + * Publish sensor reading to NT + */ + public void publishStats(){ + sensorReadingPublisher.set(sensor.get()); + } + + /** + * Logs sensor reading + */ + public void logStats(){ + sensorReadingLogEntry.append(sensor.get()); + } + + /** + * Initialize networktables + * @param name + */ + private void initNT(String name){ + ntInstance = NetworkTableInstance.getDefault(); + sensorStatsTable = ntInstance.getTable(LoggingConstants.SENSOR_TABLE); + sensorReadingPublisher = sensorStatsTable.getBooleanTopic(name).publish(); + } + + /** + * Initialize logs + * @param name + */ + private void initLogs(String name){ + sensorReadingLogEntry = new BooleanLogEntry( + DataLogManager.getLog(), name + ); + } +} From bc533dba77dc8604ecd879ce9b9aff54cba59d7d Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 16:31:33 -0800 Subject: [PATCH 24/60] Make pivot ready to test --- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 125870c9..f07608a4 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -105,6 +105,10 @@ public void setVelocityReference(double velocity){ pivotMotor.setVelocityReference(velocity); } + public void setVelocityReference(double velocity){ + pivotMotor.setVelocityReference(velocity); + } + public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } From 0a99358467e0b21277f539f8ae39667e22ee14fa Mon Sep 17 00:00:00 2001 From: Jesse Date: Wed, 26 Feb 2025 15:27:56 -0800 Subject: [PATCH 25/60] Remove extra lines from rebasing --- .../frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index f07608a4..125870c9 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -105,10 +105,6 @@ public void setVelocityReference(double velocity){ pivotMotor.setVelocityReference(velocity); } - public void setVelocityReference(double velocity){ - pivotMotor.setVelocityReference(velocity); - } - public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } From 33507c6135935c1f1666d2ab01ed0e5afb5fcc79 Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Wed, 26 Feb 2025 17:43:15 -0800 Subject: [PATCH 26/60] tuned pivot --- .../Pivot/PivotToHorizontalCommand.java | 25 ++++++ src/main/java/frc/robot/Constants.java | 13 +-- src/main/java/frc/robot/RobotContainer.java | 84 ++++++++++++------- .../Intake/Pivot/PivotSubsystem.java | 13 ++- 4 files changed, 89 insertions(+), 46 deletions(-) create mode 100644 src/main/java/frc/robot/Commands/Intake/Pivot/PivotToHorizontalCommand.java diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToHorizontalCommand.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToHorizontalCommand.java new file mode 100644 index 00000000..a12f4e84 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotToHorizontalCommand.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Intake.Pivot; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; + +public class PivotToHorizontalCommand extends Command{ + private final PivotSubsystem pivotSubsystem; + + public PivotToHorizontalCommand(PivotSubsystem pivotSubsystem){ + this.pivotSubsystem = pivotSubsystem; + this.addRequirements(pivotSubsystem); + } + + @Override + public void initialize(){ + pivotSubsystem.setPositionReferenceWithVoltage(PivotConstants.PIVOT_HORIZONTAL); + } + + @Override + public boolean isFinished(){ + return Math.abs(pivotSubsystem.getClosedLoopError()) + < PivotConstants.PIVOT_TOLERANCE; + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c7f9a4fa..409e0b15 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -33,10 +33,10 @@ public static class PivotConstants{ public static final int PIVOT_CAN_ID = 14; public static final String PIVOT_CAN_NAME = "rio"; - public static final double PIVOT_KP = 0.; + public static final double PIVOT_KP = 7; public static final double PIVOT_KI = 0.; - public static final double PIVOT_KD = 0.; - public static final double PIVOT_KG = 0.; + public static final double PIVOT_KD = 5; + public static final double PIVOT_KG = 100.; public static final double PIVOT_KV = 0.; public static final double PIVOT_KS = 0.; @@ -48,11 +48,12 @@ public static class PivotConstants{ public static final double PIVOT_TOLERANCE = 0.1; public static final double ROTOR_TO_SENSOR_RATIO = 20. / (2. * Math.PI); - public static final double PIVOT_INIT_POS = Units.degreesToRadians(94); - public static final double PIVOT_MAX_POS = Units.degreesToRadians(94); + public static final double PIVOT_INIT_POS = Units.degreesToRadians(95); + public static final double PIVOT_HORIZONTAL = Units.degreesToRadians(0); + public static final double PIVOT_MAX_POS = Units.degreesToRadians(95); public static final double PIVOT_MIN_POS = Units.degreesToRadians(-45); - public static final double PIVOT_RAMP_RATE = 0.02; + public static final double PIVOT_RAMP_RATE = 0.03; public static final double PIVOT_CURRENT_LIMIT = 100.; } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index a0fcc068..d722a7fa 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -21,6 +21,7 @@ import frc.robot.subsystems.Intake.Roller.RollerSubsystem; import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; +import frc.robot.Commands.Intake.Pivot.PivotToHorizontalCommand; import frc.robot.Commands.Intake.Pivot.PivotToOuttakeCommand; import frc.robot.Commands.Intake.Pivot.PivotToSourceCommand; import frc.robot.Commands.Intake.Pivot.PivotUp90Command; @@ -77,25 +78,25 @@ private void configureBindings() { * the robot is controlled along its own axes, otherwise controls apply to the field axes by default. If the * swerve aim button is held down, the robot will rotate automatically to always face a target, and only * translation will be manually controllable. */ - swerveSubsystem.setDefaultCommand( - new RunCommand(() -> { - swerveSubsystem.setDrivePowers( - driveController.getForwardPower(), - driveController.getLeftPower(), - driveController.getRotatePower() - ); - }, - swerveSubsystem - ) - ); - - /* Pressing the button resets the field axes to the current robot axes. */ - driveController.bindDriverHeadingReset( - () ->{ - swerveSubsystem.resetDriverHeading(); - }, - swerveSubsystem - ); + // swerveSubsystem.setDefaultCommand( + // new RunCommand(() -> { + // swerveSubsystem.setDrivePowers( + // driveController.getForwardPower(), + // driveController.getLeftPower(), + // driveController.getRotatePower() + // ); + // }, + // swerveSubsystem + // ) + // ); + + // /* Pressing the button resets the field axes to the current robot axes. */ + // driveController.bindDriverHeadingReset( + // () ->{ + // swerveSubsystem.resetDriverHeading(); + // }, + // swerveSubsystem + // ); } /** @@ -127,14 +128,14 @@ private void constructMechController(){ * Binds the intake commands to the mech controller */ private void bindIntake(){ - pivotSubsystem.setDefaultCommand( - new RunCommand(() -> { - pivotSubsystem.setVelocityReference(mechController.getLeftY()); - }, - pivotSubsystem - ) - .onlyWhile(() -> Math.abs(mechController.getLeftY()) > 0.05) - ); + // pivotSubsystem.setDefaultCommand( + // new RunCommand(() -> { + // pivotSubsystem.setVelocityReference(mechController.getLeftY()); + // }, + // pivotSubsystem + // ) + // .onlyWhile(() -> Math.abs(mechController.getLeftY()) > 0.05) + // ); rollerSubsystem.setDefaultCommand(new ConditionalCommand( new InstantCommand( () -> { @@ -146,9 +147,28 @@ private void bindIntake(){ }, rollerSubsystem), () -> rollerSubsystem.getIntakeSensor())); + // mechController.povUp().onTrue( + // new ConditionalCommand( + // new PivotToSourceCommand(pivotSubsystem), + // new PivotToHorizontalCommand(pivotSubsystem).andThen(new PivotToSourceCommand(pivotSubsystem)), + // () -> pivotSubsystem.getPosition() > 0 + // )); + + // mechController.L1().onTrue( + // new ConditionalCommand( + // new PivotUp90Command(pivotSubsystem), + // new PivotToHorizontalCommand(pivotSubsystem).andThen(new PivotUp90Command(pivotSubsystem)), + // () -> pivotSubsystem.getPosition() > 0 + // )); + + mechController.povUp().onTrue( + new PivotToSourceCommand(pivotSubsystem) + ); + mechController.L1().onTrue( + new PivotUp90Command(pivotSubsystem) + ); + mechController.povDown().onTrue(new PivotToOuttakeCommand(pivotSubsystem)); - mechController.povUp().onTrue(new PivotToSourceCommand(pivotSubsystem)); - mechController.L1().onTrue(new PivotUp90Command(pivotSubsystem)); } /** @@ -163,9 +183,9 @@ private void startLog(){ * Links vision and swerve */ private void setVisionDataInterface(){ - visionSubsystem2.setInterface(swerveSubsystem::addVisionMeasurements); - visionSubsystem3.setInterface(swerveSubsystem::addVisionMeasurements); - visionSubsystem4.setInterface(swerveSubsystem::addVisionMeasurements); + // visionSubsystem2.setInterface(swerveSubsystem::addVisionMeasurements); + // visionSubsystem3.setInterface(swerveSubsystem::addVisionMeasurements); + // visionSubsystem4.setInterface(swerveSubsystem::addVisionMeasurements); } } diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 125870c9..57ae1792 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -33,13 +33,6 @@ public class PivotSubsystem extends SubsystemBase{ .withKP(PivotConstants.PIVOT_KP) .withKI(PivotConstants.PIVOT_KI) .withKD(PivotConstants.PIVOT_KD) - .withKG(PivotConstants.PIVOT_KG) - .withKV(PivotConstants.PIVOT_KV) - .withGravityType(GravityTypeValue.Arm_Cosine) - ) - .withClosedLoopGeneral( - new ClosedLoopGeneralConfigs() - .withContinuousWrap(true) ) .withClosedLoopRamps( new ClosedLoopRampsConfigs() @@ -89,7 +82,7 @@ public void setPositionReferenceWithVoltage(double position){ */ public void setPositionReference(double positionReference){ if (positionReference > pivotMotor.getPosition()) { - arbFF = feedforward.calculate(positionReference, 0.0); + arbFF = feedforward.calculate(positionReference, 5); } else { arbFF = 0; @@ -108,4 +101,8 @@ public void setVelocityReference(double velocity){ public double getClosedLoopError(){ return pivotMotor.getClosedLoopError(); } + + public double getPosition() { + return pivotMotor.getPosition(); + } } From 35592048dd2c0869aaa2cbe12188ac3eacbed69e Mon Sep 17 00:00:00 2001 From: Tony Wu Date: Wed, 26 Feb 2025 20:52:24 -0800 Subject: [PATCH 27/60] contruct both bottom cameras disabled top --- .OutlineViewer/outlineviewer.json | 3 --- src/main/java/frc/robot/Constants.java | 6 +++--- src/main/java/frc/robot/RobotContainer.java | 16 ++++++++++------ 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/.OutlineViewer/outlineviewer.json b/.OutlineViewer/outlineviewer.json index 91c7a425..6ab691d6 100644 --- a/.OutlineViewer/outlineviewer.json +++ b/.OutlineViewer/outlineviewer.json @@ -3,9 +3,6 @@ "mode": "Client (NT4)", "serverTeam": "192" }, - "Retained Values": { - "open": false - }, "transitory": { "MotorStats": { "open": true diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 23c08cf8..d740dc3c 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -136,10 +136,10 @@ public static class VisionConstants{ PoseStrategy.LOWEST_AMBIGUITY ), new CameraConfig( - "4", + "2", new Transform3d( - 0.127, 0, 1.13, - new Rotation3d(0, -Math.PI / 9., 0.) + 0.2921, 0.2921, 0.1651, + new Rotation3d(0, -Math.PI / 9., -Math.PI/18) ), PoseStrategy.LOWEST_AMBIGUITY ) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 58f27688..b878e04f 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -28,14 +28,17 @@ public class RobotContainer { private PS5DriveController driveController; private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); - private final VisionSubsystem visionSubsystem2 = new VisionSubsystem( - VisionConstants.cameraConfigs[1] - ); + // private final VisionSubsystem visionSubsystem1 = new VisionSubsystem( + // VisionConstants.cameraConfigs[1] + // ); + // private final VisionSubsystem visionSubsystem2 = new VisionSubsystem( + // VisionConstants.cameraConfigs[2] + // ); private final VisionSubsystem visionSubsystem3 = new VisionSubsystem( - VisionConstants.cameraConfigs[2] + VisionConstants.cameraConfigs[3] ); private final VisionSubsystem visionSubsystem4 = new VisionSubsystem( - VisionConstants.cameraConfigs[3] + VisionConstants.cameraConfigs[4] ); /** The container for the robot. Contains subsystems, OI devices, and commands. */ @@ -111,7 +114,8 @@ private void startLog(){ * Links vision and swerve */ private void setVisionDataInterface(){ - visionSubsystem2.setInterface(swerveSubsystem::addVisionMeasurements); + //visionSubsystem1.setInterface(swerveSubsystem::addVisionMeasurements); + //visionSubsystem2.setInterface(swerveSubsystem::addVisionMeasurements); visionSubsystem3.setInterface(swerveSubsystem::addVisionMeasurements); visionSubsystem4.setInterface(swerveSubsystem::addVisionMeasurements); From c8f4c1b27aa98abec3709cb113029c0cec0c0cbb Mon Sep 17 00:00:00 2001 From: Tony Wu Date: Wed, 26 Feb 2025 21:01:12 -0800 Subject: [PATCH 28/60] fixed --- src/main/java/frc/robot/RobotContainer.java | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index b878e04f..969418cd 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -29,16 +29,16 @@ public class RobotContainer { private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); // private final VisionSubsystem visionSubsystem1 = new VisionSubsystem( - // VisionConstants.cameraConfigs[1] + // VisionConstants.cameraConfigs[0] // ); // private final VisionSubsystem visionSubsystem2 = new VisionSubsystem( - // VisionConstants.cameraConfigs[2] + // VisionConstants.cameraConfigs[1] // ); private final VisionSubsystem visionSubsystem3 = new VisionSubsystem( - VisionConstants.cameraConfigs[3] + VisionConstants.cameraConfigs[2] ); private final VisionSubsystem visionSubsystem4 = new VisionSubsystem( - VisionConstants.cameraConfigs[4] + VisionConstants.cameraConfigs[3] ); /** The container for the robot. Contains subsystems, OI devices, and commands. */ From c0265fe58b39e26a0627877f4b844567b5b577d7 Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Wed, 26 Feb 2025 21:22:17 -0800 Subject: [PATCH 29/60] t:wq retune --- src/main/java/frc/robot/Constants.java | 16 ++++---- src/main/java/frc/robot/RobotContainer.java | 41 +++++++++---------- .../Intake/Pivot/PivotSubsystem.java | 6 ++- src/main/java/frc/robot/util/LoggedTalon.java | 4 ++ 4 files changed, 37 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 409e0b15..ac70cdec 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -33,25 +33,25 @@ public static class PivotConstants{ public static final int PIVOT_CAN_ID = 14; public static final String PIVOT_CAN_NAME = "rio"; - public static final double PIVOT_KP = 7; + public static final double PIVOT_KP = 5.4; public static final double PIVOT_KI = 0.; - public static final double PIVOT_KD = 5; - public static final double PIVOT_KG = 100.; + public static final double PIVOT_KD = .6; + public static final double PIVOT_KG = 500.; public static final double PIVOT_KV = 0.; public static final double PIVOT_KS = 0.; public static final double PIVOT_MANUAL_SPEED = 0.15; - public static final double SOURCE_POS = Units.degreesToRadians(50); - public static final double OUTTAKE_POS = Units.degreesToRadians(-45); + public static final double SOURCE_POS = Units.degreesToRadians(45.); + public static final double OUTTAKE_POS = Units.degreesToRadians(-45.); public static final double PIVOT_TOLERANCE = 0.1; public static final double ROTOR_TO_SENSOR_RATIO = 20. / (2. * Math.PI); - public static final double PIVOT_INIT_POS = Units.degreesToRadians(95); + public static final double PIVOT_INIT_POS = Units.degreesToRadians(95.); public static final double PIVOT_HORIZONTAL = Units.degreesToRadians(0); - public static final double PIVOT_MAX_POS = Units.degreesToRadians(95); - public static final double PIVOT_MIN_POS = Units.degreesToRadians(-45); + public static final double PIVOT_MAX_POS = Units.degreesToRadians(95.); + public static final double PIVOT_MIN_POS = Units.degreesToRadians(-45.); public static final double PIVOT_RAMP_RATE = 0.03; public static final double PIVOT_CURRENT_LIMIT = 100.; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d722a7fa..48e89fe3 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -78,25 +78,25 @@ private void configureBindings() { * the robot is controlled along its own axes, otherwise controls apply to the field axes by default. If the * swerve aim button is held down, the robot will rotate automatically to always face a target, and only * translation will be manually controllable. */ - // swerveSubsystem.setDefaultCommand( - // new RunCommand(() -> { - // swerveSubsystem.setDrivePowers( - // driveController.getForwardPower(), - // driveController.getLeftPower(), - // driveController.getRotatePower() - // ); - // }, - // swerveSubsystem - // ) - // ); + swerveSubsystem.setDefaultCommand( + new RunCommand(() -> { + swerveSubsystem.setDrivePowers( + driveController.getForwardPower(), + driveController.getLeftPower(), + driveController.getRotatePower() + ); + }, + swerveSubsystem + ) + ); - // /* Pressing the button resets the field axes to the current robot axes. */ - // driveController.bindDriverHeadingReset( - // () ->{ - // swerveSubsystem.resetDriverHeading(); - // }, - // swerveSubsystem - // ); + /* Pressing the button resets the field axes to the current robot axes. */ + driveController.bindDriverHeadingReset( + () ->{ + swerveSubsystem.resetDriverHeading(); + }, + swerveSubsystem + ); } /** @@ -129,12 +129,11 @@ private void constructMechController(){ */ private void bindIntake(){ // pivotSubsystem.setDefaultCommand( - // new RunCommand(() -> { - // pivotSubsystem.setVelocityReference(mechController.getLeftY()); + // new InstantCommand(() -> { + // pivotSubsystem.setPower(mechController.getLeftY()); // }, // pivotSubsystem // ) - // .onlyWhile(() -> Math.abs(mechController.getLeftY()) > 0.05) // ); rollerSubsystem.setDefaultCommand(new ConditionalCommand( diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 57ae1792..6455d03c 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -85,7 +85,7 @@ public void setPositionReference(double positionReference){ arbFF = feedforward.calculate(positionReference, 5); } else { - arbFF = 0; + arbFF = feedforward.calculate(positionReference, .1, .01); } pivotMotor.setPositionReferenceWithArbFF(positionReference, arbFF); } @@ -105,4 +105,8 @@ public double getClosedLoopError(){ public double getPosition() { return pivotMotor.getPosition(); } + + public void setPower(double speed) { + pivotMotor.setPower(speed); + } } diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index ed399128..d00bcf51 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -170,6 +170,10 @@ public void setPosition(double position){ } } + public void setPower(double speed) { + motor.set(speed); + } + /** * Configures drive motor's PIDSV * @param p kP From a5c3570f73fbdcca11b80fb1d7853401a17831ca Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 20 Feb 2025 16:35:38 -0800 Subject: [PATCH 30/60] Update krakens to torque current FOC control --- src/main/java/frc/robot/util/LoggedTalon.java | 304 ++++++++++++++++++ 1 file changed, 304 insertions(+) create mode 100644 src/main/java/frc/robot/util/LoggedTalon.java diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java new file mode 100644 index 00000000..a78f67f4 --- /dev/null +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -0,0 +1,304 @@ +package frc.robot.util; + +import java.util.EnumSet; + +import com.ctre.phoenix6.StatusCode; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; +import com.ctre.phoenix6.hardware.TalonFX; + +import edu.wpi.first.networktables.DoublePublisher; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEvent; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.util.datalog.DoubleLogEntry; +import edu.wpi.first.wpilibj.DataLogManager; + +import static frc.robot.Constants.DebugConstants.MASTER_DEBUG; +public class LoggedTalon{ + + private final TalonFX motor; + + private final int canId; + private double[] pidsvg = new double[6]; + + private NetworkTableInstance ntInstance; + private NetworkTable motorStatsTable; + + private DoublePublisher positionPublisher; + private DoublePublisher veloPublisher; + private DoublePublisher appliedVlotsPublisher; + private DoublePublisher supplyCurrentPublisher; + private DoublePublisher statorCurrentPublisher; + private DoublePublisher temperaturePublisher; + private DoublePublisher targetPositionPublisher; + private DoublePublisher targetVelocityPublisher; + + private DoubleLogEntry positionLogEntry; + private DoubleLogEntry veloLogEntry; + private DoubleLogEntry appliedVoltsLogEntry; + private DoubleLogEntry supplyCurrLogEntry; + private DoubleLogEntry statorCurrLogEntry; + private DoubleLogEntry temperatureLogEntry; + private DoubleLogEntry targetPositionLogEntry; + private DoubleLogEntry targetVelocityLogEntry; + + private double targetPosition; + private double targetVelocity; + + public LoggedTalon( + int canId, String canBusName, TalonFXConfiguration talonConfig + ){ + motor = new TalonFX(canId, canBusName); + for (int i = 0; i < 4; i++) { + boolean error = + motor.getConfigurator() + .apply(talonConfig, 0.1) + == StatusCode.OK; + if (!error) break; + } + this.canId = canId; + pidsvg = new double[] { + talonConfig.Slot0.kP, + talonConfig.Slot0.kI, + talonConfig.Slot0.kD, + talonConfig.Slot0.kS, + talonConfig.Slot0.kV, + talonConfig.Slot0.kG + }; + initNT(canId); + initLogs(canId); + if(MASTER_DEBUG){ + enableDebug(); + } + } + + /** + * Sets the motor's position reference + * @param position position reference + */ + public void setPositionReference(double position){ + targetPosition = position; + motor.setControl(new PositionTorqueCurrentFOC(position)); + } + + /** + * Sets the motor's position reference with feedforward + * @param position position reference + * @param arbFF arbitrary feedforward + */ + public void setPositionReferenceWithArbFF(double position, double arbFF){ + targetPosition = position; + motor.setControl( + new PositionTorqueCurrentFOC(position).withFeedForward(arbFF) + ); + } + /** + * Set the motor's velocity reference + * @param velocity velocity reference + */ + public void setVelocityReference(double velocity){ + targetVelocity = velocity; + motor.setControl(new VelocityTorqueCurrentFOC(velocity)); + } + + /** + * Sets the motor's position to a certain value + * @param position mechanisam position after taking the position conversion + * into account + */ + public void setPosition(double position){ + for (int i = 0; i < 4; i++) { + boolean error = motor.setPosition(position) == StatusCode.OK; + if (!error) break; + } + } + + /** + * Configures drive motor's PIDSV + * @param p kP + * @param i kI + * @param d kD + * @param s kS for static friction + * @param v kV Voltage feed forward + */ + public void configurePIDSVG(double p, double i, double d, double s, double v, + double g + ) { + Slot0Configs slot0Configs = new Slot0Configs(); + + slot0Configs.kP = p; + slot0Configs.kI = i; + slot0Configs.kD = d; + slot0Configs.kS = s; + slot0Configs.kV = v; + slot0Configs.kG = g; + + motor.getConfigurator().apply(slot0Configs); + } + + /** + * initializes network table and entries + * @param canId motor's CAN ID + */ + private void initNT(int canId){ + ntInstance = NetworkTableInstance.getDefault(); + motorStatsTable = ntInstance.getTable("MotorStats"); + + positionPublisher = motorStatsTable.getDoubleTopic( + canId + "position" + ).publish(); + + veloPublisher = motorStatsTable.getDoubleTopic(canId + "velo").publish(); + + appliedVlotsPublisher = motorStatsTable.getDoubleTopic( + canId + "appliedVolts" + ).publish(); + + supplyCurrentPublisher = motorStatsTable.getDoubleTopic( + canId + "supplyCurrent" + ).publish(); + + statorCurrentPublisher = motorStatsTable.getDoubleTopic( + canId + "statorCurrent" + ).publish(); + + temperaturePublisher = motorStatsTable.getDoubleTopic( + canId + "temperature" + ).publish(); + + targetPositionPublisher = motorStatsTable.getDoubleTopic( + canId + "targetPosition" + ).publish(); + + targetVelocityPublisher = motorStatsTable.getDoubleTopic( + canId + "targetVelocity" + ).publish(); + } + + /** + * Initializes log entries + * @param canId drive motor's CAN ID + */ + private void initLogs(int canId){ + positionLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "position" + ); + + veloLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "velo" + ); + + appliedVoltsLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "appliedVolts" + ); + + supplyCurrLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "supplyCurrent" + ); + + statorCurrLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "statorCurrent" + ); + + temperatureLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "temperature" + ); + + targetPositionLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetPosition" + ); + + targetVelocityLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetVelocity" + ); + } + + /** + * Allows changing PID through NT + */ + public void enableDebug(){ + motorStatsTable.getDoubleArrayTopic(canId + "PIDSVG").publish().set( + pidsvg + ); + motorStatsTable.addListener(canId + "PIDSVG", + EnumSet.of(NetworkTableEvent.Kind.kValueAll), + (table, key, event) -> { + configurePIDSVG( + event.valueData.value.getDoubleArray()[0], + event.valueData.value.getDoubleArray()[1], + event.valueData.value.getDoubleArray()[2], + event.valueData.value.getDoubleArray()[3], + event.valueData.value.getDoubleArray()[4], + event.valueData.value.getDoubleArray()[5] + ); + } + ); + } + /** + * Gets motor's position in rotations after taking the + * SensorToMechanismRatio into account + * @return position of the motor in rotations + */ + public double getPosition(){ + return motor.getPosition().getValueAsDouble(); + } + + /** + * Gets motor's velocity in RPS after taking the SensorToMechanismRatio into + * account + * @return velocity of the motor in RPS + */ + public double getVelocity(){ + return motor.getVelocity().getValueAsDouble(); + } + + /** + * Publishes motor stats to NT for logging + */ + public void publishStats(){ + positionPublisher.set(motor.getPosition().getValueAsDouble()); + veloPublisher.set(motor.getVelocity().getValueAsDouble()); + appliedVlotsPublisher.set(motor.getMotorVoltage().getValueAsDouble()); + supplyCurrentPublisher.set(motor.getSupplyCurrent().getValueAsDouble()); + statorCurrentPublisher.set(motor.getStatorCurrent().getValueAsDouble()); + temperaturePublisher.set(motor.getDeviceTemp().getValueAsDouble()); + targetPositionPublisher.set(targetPosition); + targetVelocityPublisher.set(targetVelocity); + } + + /** + * Loggs motor stats into log file + */ + public void logStats(){ + positionLogEntry.append( + motor.getPosition().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + veloLogEntry.append( + motor.getVelocity().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + appliedVoltsLogEntry.append( + motor.getMotorVoltage().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + supplyCurrLogEntry.append( + motor.getSupplyCurrent().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + statorCurrLogEntry.append( + motor.getStatorCurrent().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + temperatureLogEntry.append( + motor.getDeviceTemp().getValueAsDouble(), GRTUtil.getFPGATime() + ); + + targetPositionLogEntry.append(targetPosition, GRTUtil.getFPGATime()); + + targetVelocityLogEntry.append(targetVelocity, GRTUtil.getFPGATime()); + } +} \ No newline at end of file From 651e499b955929559d11433d9d4469d42d7051f7 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 20 Feb 2025 16:35:47 -0800 Subject: [PATCH 31/60] Add debug constant --- src/main/java/frc/robot/Constants.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 23c08cf8..4e3eb6b6 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -84,6 +84,10 @@ public static class LoggingConstants{ public static final String SWERVE_TABLE = "SwerveStats"; } + public static class DebugConstants{ + public static final boolean MASTER_DEBUG = true; + } + public static class VisionConstants{ public static final double FIELD_X = 17.5482504; From 7f913fb1dd1ce7eb3c2db6b90029faa45a2734dd Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 13:39:10 -0800 Subject: [PATCH 32/60] Publishes & logs close loop error --- src/main/java/frc/robot/util/LoggedTalon.java | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index a78f67f4..e35e078f 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -35,6 +35,7 @@ public class LoggedTalon{ private DoublePublisher temperaturePublisher; private DoublePublisher targetPositionPublisher; private DoublePublisher targetVelocityPublisher; + private DoublePublisher closedLoopErrorPublisher; private DoubleLogEntry positionLogEntry; private DoubleLogEntry veloLogEntry; @@ -44,6 +45,7 @@ public class LoggedTalon{ private DoubleLogEntry temperatureLogEntry; private DoubleLogEntry targetPositionLogEntry; private DoubleLogEntry targetVelocityLogEntry; + private DoubleLogEntry closedLoopErrorLogEntry; private double targetPosition; private double targetVelocity; @@ -176,6 +178,10 @@ private void initNT(int canId){ targetVelocityPublisher = motorStatsTable.getDoubleTopic( canId + "targetVelocity" ).publish(); + + closedLoopErrorPublisher = motorStatsTable.getDoubleTopic( + canId + "closedLoopError" + ).publish(); } /** @@ -214,6 +220,10 @@ private void initLogs(int canId){ targetVelocityLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "targetVelocity" ); + + closedLoopErrorLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "closedLoopError" + ); } /** @@ -255,6 +265,13 @@ public double getVelocity(){ return motor.getVelocity().getValueAsDouble(); } + /** + * Gets motor's closed loop error + * @return closed loop error + */ + public double getCloseLoopError(){ + return motor.getClosedLoopError().getValueAsDouble(); + } /** * Publishes motor stats to NT for logging */ From dd89d96589b18ac0f4b1682da8f1b413655f7d06 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 14:11:31 -0800 Subject: [PATCH 33/60] Fix naming --- src/main/java/frc/robot/util/LoggedTalon.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index e35e078f..c6525bb0 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -247,6 +247,7 @@ public void enableDebug(){ } ); } + /** * Gets motor's position in rotations after taking the * SensorToMechanismRatio into account @@ -269,9 +270,10 @@ public double getVelocity(){ * Gets motor's closed loop error * @return closed loop error */ - public double getCloseLoopError(){ + public double getClosedLoopError(){ return motor.getClosedLoopError().getValueAsDouble(); } + /** * Publishes motor stats to NT for logging */ From b5c54e951a19a44b7eb0478654b938d524544bdd Mon Sep 17 00:00:00 2001 From: Jesse Date: Sat, 22 Feb 2025 14:15:28 -0800 Subject: [PATCH 34/60] publish & log closed loop error --- src/main/java/frc/robot/util/LoggedTalon.java | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index c6525bb0..a509f818 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -286,6 +286,7 @@ public void publishStats(){ temperaturePublisher.set(motor.getDeviceTemp().getValueAsDouble()); targetPositionPublisher.set(targetPosition); targetVelocityPublisher.set(targetVelocity); + closedLoopErrorPublisher.set(motor.getClosedLoopError().getValueAsDouble()); } /** @@ -319,5 +320,9 @@ public void logStats(){ targetPositionLogEntry.append(targetPosition, GRTUtil.getFPGATime()); targetVelocityLogEntry.append(targetVelocity, GRTUtil.getFPGATime()); + + closedLoopErrorLogEntry.append( + motor.getClosedLoopError().getValueAsDouble(), GRTUtil.getFPGATime() + ); } } \ No newline at end of file From 2fc2ecf3acf7e5dd59d817011c847510afd77636 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 13:04:54 -0800 Subject: [PATCH 35/60] Untested Elevator --- .../Elevator/ElevatorToGroundCommand.java | 25 +++++ .../Elevator/ElevatorToL1Command.java | 25 +++++ .../Elevator/ElevatorToL2Command.java | 25 +++++ .../Elevator/ElevatorToL3Command.java | 25 +++++ .../Elevator/ElevatorToL4Command.java | 25 +++++ .../Elevator/ElevatorToSourceCommand.java | 25 +++++ src/main/java/frc/robot/Constants.java | 33 +++++++ .../Elevator/ElevatorSubsystem.java | 91 +++++++++++++++++++ 8 files changed, 274 insertions(+) create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java new file mode 100644 index 00000000..bf98fa7c --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToGroundCommand extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToGroundCommand(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.GROUND_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java new file mode 100644 index 00000000..8a8ff65d --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToL1Command extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToL1Command(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.L1_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java new file mode 100644 index 00000000..ff2811c2 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToL2Command extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToL2Command(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.L2_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java new file mode 100644 index 00000000..a51c4062 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToL3Command extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToL3Command(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.L3_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java new file mode 100644 index 00000000..ca811ef0 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToL4Command extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToL4Command(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.L4_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java new file mode 100644 index 00000000..eba92051 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java @@ -0,0 +1,25 @@ +package frc.robot.Commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToSourceCommand extends Command { + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToSourceCommand(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPositionReference(ElevatorConstants.SOURCE_POS); + } + + @Override + public boolean isFinished() { + return elevatorSubsystem.getClosedLoopError() + < ElevatorConstants.ELEVATOR_TOLERANCE; + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4e3eb6b6..8e4daf93 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -27,6 +27,39 @@ public static class OperatorConstants { public static final int kDriverControllerPort = 0; } + public static class ElevatorConstants { + public static final double SOURCE_POS= 0.0; //change + public static final double L1_POS = 0.5; //change + public static final double L2_POS = 0.0; //change + public static final double L3_POS = 0.0; //change + public static final double L4_POS = 0.0; //change + public static final double GROUND_POS = 0.0; + + public static final double ELEVATOR_TOLERANCE = 8; //change + + public static final int MOTOR_ID = 13; //change + public static final int LIMIT_ID = 0; //change + + public static final double kP = 0.6; //change + public static final double kI = 0; //change + public static final double kD = 0; //change + public static final double kS = 4; //chang + + public static final double FORWARD_LIMIT = 88; //change + public static final double REVERSE_LIMIT = 0; //change + + public static final double CURRENT_LIMIT = 100; + + public static final double GEAR_RATIO = 20; //motor to axle + public static final double AXLE_RADIUS = 6. * .289 * .0254; //in meters + + public static final double TICKS_TO_DIST = 2. * Math.PI * AXLE_RADIUS / GEAR_RATIO; + public static final double DIST_TO_TICKS = 1. / TICKS_TO_DIST; + + public static final double dutyCycletoticks = 88.; + + public static final boolean ELEVATOR_DEBUG = true; + } /** Constants for the swerve subsystem. */ public static class SwerveConstants { public static final int FL_DRIVE = 0; diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java new file mode 100644 index 00000000..9997f3fe --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -0,0 +1,91 @@ +package frc.robot.subsystems.Elevator; + + +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.SoftwareLimitSwitchConfigs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.NeutralModeValue; + +import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.DebugConstants; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.util.LoggedTalon; + +/** +* Elevator Class. +*/ +public class ElevatorSubsystem extends SubsystemBase { + + //motor stuff and configs + private final LoggedTalon motor; + private final TalonFXConfiguration motorConfig; + + //limit switch + private final DigitalInput zeroLimitSwitch; + + /** + * Constructs limit switch and motors. + */ + public ElevatorSubsystem() { + motorConfig = new TalonFXConfiguration() + .withSlot0( + new Slot0Configs() + .withKP(ElevatorConstants.kP) + .withKI(ElevatorConstants.kI) + .withKD(ElevatorConstants.kD) + .withKS(ElevatorConstants.kS) + ) + .withMotorOutput( + new MotorOutputConfigs() + .withNeutralMode(NeutralModeValue.Brake) + ) + .withSoftwareLimitSwitch( + new SoftwareLimitSwitchConfigs() + .withForwardSoftLimitEnable(true) + .withForwardSoftLimitThreshold(ElevatorConstants.FORWARD_LIMIT) + .withReverseSoftLimitEnable(true) + .withReverseSoftLimitThreshold(ElevatorConstants.REVERSE_LIMIT) + ) + .withCurrentLimits( + new CurrentLimitsConfigs() + .withStatorCurrentLimitEnable(true) + .withStatorCurrentLimit(ElevatorConstants.CURRENT_LIMIT) + ); + + motor = new LoggedTalon( + ElevatorConstants.MOTOR_ID, "can", motorConfig + ); + + zeroLimitSwitch = new DigitalInput(ElevatorConstants.LIMIT_ID); + } + + @Override + public void periodic() { + if(zeroLimitSwitch.get()){ + motor.setPosition(0); + } + motor.logStats(); + if(DebugConstants.MASTER_DEBUG || ElevatorConstants.ELEVATOR_DEBUG) { + motor.publishStats(); + } + } + + /** + * Sets the elevator to a specific position. + * @param positionReference target position + */ + public void setPositionReference(double positionReference){ + motor.setPositionReference(positionReference); + } + + /** + * Gets the closed loop error of the motor. + * @return closed loop error + */ + public double getClosedLoopError(){ + return motor.getClosedLoopError(); + } +} \ No newline at end of file From b1256633c5969b3c9ba99eb365cfe109d08ffea2 Mon Sep 17 00:00:00 2001 From: Jesse Date: Sun, 23 Feb 2025 16:37:08 -0800 Subject: [PATCH 36/60] make elevator ready to test --- src/main/java/frc/robot/RobotContainer.java | 29 +++++++++++++++++++ .../Elevator/ElevatorSubsystem.java | 4 +++ 2 files changed, 33 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 58f27688..e82227f9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -12,10 +12,18 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.RunCommand; +import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; +import frc.robot.Commands.Elevator.ElevatorToGroundCommand; +import frc.robot.Commands.Elevator.ElevatorToL1Command; +import frc.robot.Commands.Elevator.ElevatorToL2Command; +import frc.robot.Commands.Elevator.ElevatorToL3Command; +import frc.robot.Commands.Elevator.ElevatorToL4Command; +import frc.robot.Commands.Elevator.ElevatorToSourceCommand; import frc.robot.Constants.VisionConstants; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -26,7 +34,9 @@ public class RobotContainer { private PS5DriveController driveController; + private CommandPS5Controller mechController; + private final ElevatorSubsystem elevatorSubsystem = new ElevatorSubsystem(); private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); private final VisionSubsystem visionSubsystem2 = new VisionSubsystem( VisionConstants.cameraConfigs[1] @@ -41,6 +51,7 @@ public class RobotContainer { /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); + constructMechController(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -99,6 +110,24 @@ private void constructDriveController(){ driveController.setDeadZone(0.05); } + private void constructMechController(){ + mechController = new CommandPS5Controller(0); + elevatorSubsystem.setDefaultCommand( + new RunCommand( + () -> { + elevatorSubsystem.setVelocityReference(mechController.getLeftY()); + }, + elevatorSubsystem + ) + ); + mechController.circle().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); + mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); + mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); + mechController.L1().onTrue(new ElevatorToL4Command(elevatorSubsystem)); + mechController.R1().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); + } + /** * Starts datalog at /u/logs */ diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java index 9997f3fe..3a5d8b0f 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -80,6 +80,10 @@ public void periodic() { public void setPositionReference(double positionReference){ motor.setPositionReference(positionReference); } + + public void setVelocityReference(double velocityReference){ + motor.setVelocityReference(velocityReference); + } /** * Gets the closed loop error of the motor. From 8c09de44c1804c007877bfba1442d8466b48ebe8 Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 18 Feb 2025 17:40:22 -0800 Subject: [PATCH 37/60] Force the drive controller to be PS5 controller --- src/main/java/frc/robot/RobotContainer.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e82227f9..2f432967 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,6 +4,8 @@ package frc.robot; +import frc.robot.controllers.BaseDriveController; +import frc.robot.controllers.DualJoystickDriveController; import frc.robot.controllers.PS5DriveController; import com.pathplanner.lib.commands.PathPlannerAuto; From 3996ae5ebf5a2d7ead2079bf6102232f61de9bff Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 18 Feb 2025 17:40:22 -0800 Subject: [PATCH 38/60] Force the drive controller to be PS5 controller --- src/main/java/frc/robot/RobotContainer.java | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 2f432967..e82227f9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,8 +4,6 @@ package frc.robot; -import frc.robot.controllers.BaseDriveController; -import frc.robot.controllers.DualJoystickDriveController; import frc.robot.controllers.PS5DriveController; import com.pathplanner.lib.commands.PathPlannerAuto; From b84f4e16fddc0ce72fa89b9e43c517d971066a53 Mon Sep 17 00:00:00 2001 From: Jesse Date: Tue, 25 Feb 2025 13:53:34 -0800 Subject: [PATCH 39/60] Bind elevator in seperate method --- src/main/java/frc/robot/RobotContainer.java | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e82227f9..96d3b74d 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -52,6 +52,7 @@ public class RobotContainer { public RobotContainer() { constructDriveController(); constructMechController(); + bindElevator(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -110,8 +111,17 @@ private void constructDriveController(){ driveController.setDeadZone(0.05); } + /** + * Constructs mech controller + */ private void constructMechController(){ mechController = new CommandPS5Controller(0); + } + + /** + * Binds elevator commands to mech controller + */ + private void bindElevator(){ elevatorSubsystem.setDefaultCommand( new RunCommand( () -> { @@ -120,12 +130,12 @@ private void constructMechController(){ elevatorSubsystem ) ); - mechController.circle().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); - mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); + mechController.cross().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); - mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); - mechController.L1().onTrue(new ElevatorToL4Command(elevatorSubsystem)); - mechController.R1().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); + mechController.circle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); + mechController.triangle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); + // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); } /** From d083dbd09442029fb6242c4603000b4d444fe868 Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Tue, 25 Feb 2025 15:33:53 -0800 Subject: [PATCH 40/60] fix imports after rebase --- .../java/frc/robot/Commands/AutoAlignCommand.java | 2 +- .../Commands/Elevator/ElevatorToGroundCommand.java | 2 +- .../robot/Commands/Elevator/ElevatorToL1Command.java | 2 +- .../robot/Commands/Elevator/ElevatorToL2Command.java | 2 +- .../robot/Commands/Elevator/ElevatorToL3Command.java | 2 +- .../robot/Commands/Elevator/ElevatorToL4Command.java | 2 +- .../Commands/Elevator/ElevatorToSourceCommand.java | 2 +- src/main/java/frc/robot/RobotContainer.java | 12 ++++++------ 8 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/Commands/AutoAlignCommand.java b/src/main/java/frc/robot/Commands/AutoAlignCommand.java index b13b897c..7df51db2 100644 --- a/src/main/java/frc/robot/Commands/AutoAlignCommand.java +++ b/src/main/java/frc/robot/Commands/AutoAlignCommand.java @@ -1,4 +1,4 @@ -package frc.robot.Commands; +package frc.robot.commands; import frc.robot.subsystems.swerve.SwerveSubsystem; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java index bf98fa7c..0206025e 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java index 8a8ff65d..5cf590f7 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java index ff2811c2..dbc5a5a0 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java index a51c4062..5abfbe60 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java index ca811ef0..7e653d58 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java index eba92051..69558c1b 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java @@ -1,4 +1,4 @@ -package frc.robot.Commands.Elevator; +package frc.robot.commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 96d3b74d..c45fd729 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -18,13 +18,13 @@ import frc.robot.subsystems.Elevator.ElevatorSubsystem; import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; -import frc.robot.Commands.Elevator.ElevatorToGroundCommand; -import frc.robot.Commands.Elevator.ElevatorToL1Command; -import frc.robot.Commands.Elevator.ElevatorToL2Command; -import frc.robot.Commands.Elevator.ElevatorToL3Command; -import frc.robot.Commands.Elevator.ElevatorToL4Command; -import frc.robot.Commands.Elevator.ElevatorToSourceCommand; import frc.robot.Constants.VisionConstants; +import frc.robot.commands.Elevator.ElevatorToGroundCommand; +import frc.robot.commands.Elevator.ElevatorToL1Command; +import frc.robot.commands.Elevator.ElevatorToL2Command; +import frc.robot.commands.Elevator.ElevatorToL3Command; +import frc.robot.commands.Elevator.ElevatorToL4Command; +import frc.robot.commands.Elevator.ElevatorToSourceCommand; /** * This class is where the bulk of the robot should be declared. Since Command-based is a * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} From 3c801fdb17d91a83cc8ad18ecb07fc1dac23b29b Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Tue, 25 Feb 2025 19:55:38 -0800 Subject: [PATCH 41/60] elevator mid-tune --- .../ElevatorToLimitSwitchCommand.java | 24 +++++++++++++++++ src/main/java/frc/robot/Constants.java | 18 ++++++------- src/main/java/frc/robot/RobotContainer.java | 12 ++++++--- .../Elevator/ElevatorSubsystem.java | 26 ++++++++++++++----- src/main/java/frc/robot/util/LoggedTalon.java | 4 +++ 5 files changed, 65 insertions(+), 19 deletions(-) create mode 100644 src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java new file mode 100644 index 00000000..2efce0c2 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java @@ -0,0 +1,24 @@ +package frc.robot.commands.Elevator; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.Elevator.ElevatorSubsystem; + +public class ElevatorToLimitSwitchCommand extends Command{ + private ElevatorSubsystem elevatorSubsystem; + + public ElevatorToLimitSwitchCommand(ElevatorSubsystem elevatorSubsystem) { + this.elevatorSubsystem = elevatorSubsystem; + addRequirements(elevatorSubsystem); + } + + @Override + public void initialize() { + elevatorSubsystem.setPower(-.3); + } + + @Override + public void end(boolean interrupted) { + elevatorSubsystem.setPower(0); + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 8e4daf93..b1405149 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -28,11 +28,13 @@ public static class OperatorConstants { } public static class ElevatorConstants { + + public static final double dutyCycletoticks = 123.; public static final double SOURCE_POS= 0.0; //change - public static final double L1_POS = 0.5; //change - public static final double L2_POS = 0.0; //change - public static final double L3_POS = 0.0; //change - public static final double L4_POS = 0.0; //change + public static final double L1_POS = 0.3 * dutyCycletoticks; //change + public static final double L2_POS = 0.5 * dutyCycletoticks; //change + public static final double L3_POS = 0.6 * dutyCycletoticks; //change + public static final double L4_POS = 0.9 * dutyCycletoticks; //change public static final double GROUND_POS = 0.0; public static final double ELEVATOR_TOLERANCE = 8; //change @@ -40,12 +42,12 @@ public static class ElevatorConstants { public static final int MOTOR_ID = 13; //change public static final int LIMIT_ID = 0; //change - public static final double kP = 0.6; //change + public static final double kP = 4; //change public static final double kI = 0; //change public static final double kD = 0; //change - public static final double kS = 4; //chang + public static final double arbFF = 2; //chang - public static final double FORWARD_LIMIT = 88; //change + public static final double FORWARD_LIMIT = 126; //change public static final double REVERSE_LIMIT = 0; //change public static final double CURRENT_LIMIT = 100; @@ -56,8 +58,6 @@ public static class ElevatorConstants { public static final double TICKS_TO_DIST = 2. * Math.PI * AXLE_RADIUS / GEAR_RATIO; public static final double DIST_TO_TICKS = 1. / TICKS_TO_DIST; - public static final double dutyCycletoticks = 88.; - public static final boolean ELEVATOR_DEBUG = true; } /** Constants for the swerve subsystem. */ diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index c45fd729..08fd5e2e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -24,6 +24,7 @@ import frc.robot.commands.Elevator.ElevatorToL2Command; import frc.robot.commands.Elevator.ElevatorToL3Command; import frc.robot.commands.Elevator.ElevatorToL4Command; +import frc.robot.commands.Elevator.ElevatorToLimitSwitchCommand; import frc.robot.commands.Elevator.ElevatorToSourceCommand; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -115,7 +116,7 @@ private void constructDriveController(){ * Constructs mech controller */ private void constructMechController(){ - mechController = new CommandPS5Controller(0); + mechController = new CommandPS5Controller(1); } /** @@ -125,17 +126,20 @@ private void bindElevator(){ elevatorSubsystem.setDefaultCommand( new RunCommand( () -> { - elevatorSubsystem.setVelocityReference(mechController.getLeftY()); + elevatorSubsystem.setPower(-mechController.getLeftY()); }, elevatorSubsystem ) - ); + ); + mechController.L1().whileTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); mechController.cross().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); - mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); + mechController.square().onTrue(new ElevatorToL1Command(elevatorSubsystem)); mechController.circle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); mechController.triangle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + + // mechController.L1 } /** diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java index 3a5d8b0f..674d6692 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -6,6 +6,7 @@ import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.SoftwareLimitSwitchConfigs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.wpilibj.DigitalInput; @@ -22,6 +23,7 @@ public class ElevatorSubsystem extends SubsystemBase { //motor stuff and configs private final LoggedTalon motor; private final TalonFXConfiguration motorConfig; + private double arbFF; //limit switch private final DigitalInput zeroLimitSwitch; @@ -36,18 +38,18 @@ public ElevatorSubsystem() { .withKP(ElevatorConstants.kP) .withKI(ElevatorConstants.kI) .withKD(ElevatorConstants.kD) - .withKS(ElevatorConstants.kS) ) .withMotorOutput( new MotorOutputConfigs() - .withNeutralMode(NeutralModeValue.Brake) + .withNeutralMode(NeutralModeValue.Brake) + .withInverted(InvertedValue.Clockwise_Positive) ) .withSoftwareLimitSwitch( new SoftwareLimitSwitchConfigs() - .withForwardSoftLimitEnable(true) - .withForwardSoftLimitThreshold(ElevatorConstants.FORWARD_LIMIT) .withReverseSoftLimitEnable(true) + .withForwardSoftLimitEnable(true) .withReverseSoftLimitThreshold(ElevatorConstants.REVERSE_LIMIT) + .withForwardSoftLimitThreshold(ElevatorConstants.FORWARD_LIMIT) ) .withCurrentLimits( new CurrentLimitsConfigs() @@ -64,9 +66,11 @@ public ElevatorSubsystem() { @Override public void periodic() { - if(zeroLimitSwitch.get()){ + if(!zeroLimitSwitch.get()){ motor.setPosition(0); + motor.setPower(0); } + System.out.println(motor.getPosition()); motor.logStats(); if(DebugConstants.MASTER_DEBUG || ElevatorConstants.ELEVATOR_DEBUG) { motor.publishStats(); @@ -78,12 +82,22 @@ public void periodic() { * @param positionReference target position */ public void setPositionReference(double positionReference){ - motor.setPositionReference(positionReference); + if (positionReference > motor.getPosition()) { + arbFF = ElevatorConstants.arbFF; + } + else { + arbFF = 0; + } + motor.setPositionReferenceWithArbFF(positionReference, arbFF); } public void setVelocityReference(double velocityReference){ motor.setVelocityReference(velocityReference); } + + public void setPower(double power) { + motor.setPower(power); + } /** * Gets the closed loop error of the motor. diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index a509f818..d6e1f8b7 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -118,6 +118,10 @@ public void setPosition(double position){ } } + public void setPower(double power) { + motor.set(power); + } + /** * Configures drive motor's PIDSV * @param p kP From 5ad39b3b467af72633c38da45c02040eb80d71ae Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Tue, 25 Feb 2025 21:52:11 -0800 Subject: [PATCH 42/60] elevator tuned except the mech is ass bc the pullye derials so they are redoing them tomorrow --- src/main/java/frc/robot/Constants.java | 4 ++-- src/main/java/frc/robot/RobotContainer.java | 21 +++++++------------ .../Elevator/ElevatorSubsystem.java | 2 ++ 3 files changed, 12 insertions(+), 15 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index b1405149..d57bef1c 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -42,10 +42,10 @@ public static class ElevatorConstants { public static final int MOTOR_ID = 13; //change public static final int LIMIT_ID = 0; //change - public static final double kP = 4; //change + public static final double kP = 1; //change public static final double kI = 0; //change public static final double kD = 0; //change - public static final double arbFF = 2; //chang + public static final double arbFF = 30; //chang public static final double FORWARD_LIMIT = 126; //change public static final double REVERSE_LIMIT = 0; //change diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 08fd5e2e..0cbf9cb5 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -35,7 +35,7 @@ public class RobotContainer { private PS5DriveController driveController; - private CommandPS5Controller mechController; + private CommandPS5Controller mechController = new CommandPS5Controller(1); private final ElevatorSubsystem elevatorSubsystem = new ElevatorSubsystem(); private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); @@ -49,6 +49,8 @@ public class RobotContainer { VisionConstants.cameraConfigs[3] ); + private Trigger yAxis; + /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); @@ -123,19 +125,12 @@ private void constructMechController(){ * Binds elevator commands to mech controller */ private void bindElevator(){ - elevatorSubsystem.setDefaultCommand( - new RunCommand( - () -> { - elevatorSubsystem.setPower(-mechController.getLeftY()); - }, - elevatorSubsystem - ) - ); + mechController.L1().whileTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); - mechController.cross().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); - mechController.square().onTrue(new ElevatorToL1Command(elevatorSubsystem)); - mechController.circle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); - mechController.triangle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); + mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); + mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); + mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); + mechController.circle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java index 674d6692..55616239 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -11,8 +11,10 @@ import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import frc.robot.Constants.DebugConstants; import frc.robot.Constants.ElevatorConstants; +import frc.robot.controllers.MechController; import frc.robot.util.LoggedTalon; /** From 5b560a30d960a40b34986e3dd690a31ddc56c061 Mon Sep 17 00:00:00 2001 From: Jesse Date: Wed, 26 Feb 2025 14:59:31 -0800 Subject: [PATCH 43/60] Change package paths back to Commands --- .../java/frc/robot/Commands/AutoAlignCommand.java | 2 +- .../Commands/Elevator/ElevatorToGroundCommand.java | 2 +- .../Commands/Elevator/ElevatorToL1Command.java | 2 +- .../Commands/Elevator/ElevatorToL2Command.java | 2 +- .../Commands/Elevator/ElevatorToL3Command.java | 2 +- .../Commands/Elevator/ElevatorToL4Command.java | 2 +- .../Elevator/ElevatorToLimitSwitchCommand.java | 2 +- .../Commands/Elevator/ElevatorToSourceCommand.java | 2 +- src/main/java/frc/robot/RobotContainer.java | 14 +++++++------- 9 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/main/java/frc/robot/Commands/AutoAlignCommand.java b/src/main/java/frc/robot/Commands/AutoAlignCommand.java index 7df51db2..b13b897c 100644 --- a/src/main/java/frc/robot/Commands/AutoAlignCommand.java +++ b/src/main/java/frc/robot/Commands/AutoAlignCommand.java @@ -1,4 +1,4 @@ -package frc.robot.commands; +package frc.robot.Commands; import frc.robot.subsystems.swerve.SwerveSubsystem; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java index 0206025e..bf98fa7c 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToGroundCommand.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java index 5cf590f7..8a8ff65d 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL1Command.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java index dbc5a5a0..ff2811c2 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL2Command.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java index 5abfbe60..a51c4062 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL3Command.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java index 7e653d58..ca811ef0 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToL4Command.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java index 2efce0c2..d5282fd7 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java index 69558c1b..eba92051 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToSourceCommand.java @@ -1,4 +1,4 @@ -package frc.robot.commands.Elevator; +package frc.robot.Commands.Elevator; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants.ElevatorConstants; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 0cbf9cb5..46f69edd 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -19,13 +19,13 @@ import frc.robot.subsystems.Vision.VisionSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; import frc.robot.Constants.VisionConstants; -import frc.robot.commands.Elevator.ElevatorToGroundCommand; -import frc.robot.commands.Elevator.ElevatorToL1Command; -import frc.robot.commands.Elevator.ElevatorToL2Command; -import frc.robot.commands.Elevator.ElevatorToL3Command; -import frc.robot.commands.Elevator.ElevatorToL4Command; -import frc.robot.commands.Elevator.ElevatorToLimitSwitchCommand; -import frc.robot.commands.Elevator.ElevatorToSourceCommand; +import frc.robot.Commands.Elevator.ElevatorToGroundCommand; +import frc.robot.Commands.Elevator.ElevatorToL1Command; +import frc.robot.Commands.Elevator.ElevatorToL2Command; +import frc.robot.Commands.Elevator.ElevatorToL3Command; +import frc.robot.Commands.Elevator.ElevatorToL4Command; +import frc.robot.Commands.Elevator.ElevatorToLimitSwitchCommand; +import frc.robot.Commands.Elevator.ElevatorToSourceCommand; /** * This class is where the bulk of the robot should be declared. Since Command-based is a * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} From 63f247c0402005257db359aa4ef4be0fd154b859 Mon Sep 17 00:00:00 2001 From: Jesse Date: Mon, 24 Feb 2025 19:05:47 -0800 Subject: [PATCH 44/60] Add methods to allow voltage requests to account for motor not under canivore --- src/main/java/frc/robot/util/LoggedTalon.java | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index d6e1f8b7..789e8f69 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -6,7 +6,9 @@ import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; +import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; +import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; import edu.wpi.first.networktables.DoublePublisher; @@ -86,6 +88,15 @@ public void setPositionReference(double position){ motor.setControl(new PositionTorqueCurrentFOC(position)); } + /** + * Sets the motor's position reference with voltage + * @param position position reference + */ + public void setPositionReferenceWithVoltage(double position){ + targetPosition = position; + motor.setControl(new PositionVoltage(position)); + } + /** * Sets the motor's position reference with feedforward * @param position position reference @@ -97,6 +108,7 @@ public void setPositionReferenceWithArbFF(double position, double arbFF){ new PositionTorqueCurrentFOC(position).withFeedForward(arbFF) ); } + /** * Set the motor's velocity reference * @param velocity velocity reference @@ -105,6 +117,14 @@ public void setVelocityReference(double velocity){ targetVelocity = velocity; motor.setControl(new VelocityTorqueCurrentFOC(velocity)); } + /** + * Sets the motor's velocity reference with voltage + * @param velocity velocity reference + */ + public void setVelocityReferenceWithVoltage(double velocity){ + targetVelocity = velocity; + motor.setControl(new VelocityVoltage(velocity)); + } /** * Sets the motor's position to a certain value From e6d78ff86290e4e3b70ebed0c8524cef5c7ac8ab Mon Sep 17 00:00:00 2001 From: Jesse Date: Wed, 26 Feb 2025 15:16:11 -0800 Subject: [PATCH 45/60] Allow setting current and duty cycle requests --- src/main/java/frc/robot/util/LoggedTalon.java | 44 +++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index 789e8f69..70c237dd 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -2,11 +2,15 @@ import java.util.EnumSet; +import javax.xml.crypto.Data; + import com.ctre.phoenix6.StatusCode; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.DutyCycleOut; import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.controls.TorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC; import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.hardware.TalonFX; @@ -37,6 +41,8 @@ public class LoggedTalon{ private DoublePublisher temperaturePublisher; private DoublePublisher targetPositionPublisher; private DoublePublisher targetVelocityPublisher; + private DoublePublisher targetTorqueCurrentFOCPublisher; + private DoublePublisher targetDutyCyclePublisher; private DoublePublisher closedLoopErrorPublisher; private DoubleLogEntry positionLogEntry; @@ -47,10 +53,14 @@ public class LoggedTalon{ private DoubleLogEntry temperatureLogEntry; private DoubleLogEntry targetPositionLogEntry; private DoubleLogEntry targetVelocityLogEntry; + private DoubleLogEntry targetTorqueCurrentFOCLogEntry; + private DoubleLogEntry targetDutyCycleLogEntry; private DoubleLogEntry closedLoopErrorLogEntry; private double targetPosition; private double targetVelocity; + private double targetTorqueCurrentFOC; + private double targetDutyCycle; public LoggedTalon( int canId, String canBusName, TalonFXConfiguration talonConfig @@ -126,6 +136,24 @@ public void setVelocityReferenceWithVoltage(double velocity){ motor.setControl(new VelocityVoltage(velocity)); } + /** + * Set the current of the motor directly + * @param current target current output + */ + public void setTorqueCurrentFOC(double current){ + targetTorqueCurrentFOC = current; + motor.setControl(new TorqueCurrentFOC(current)); + } + + /** + * Set duty cycle output + * @param output duty cycle output from -1.0 to 1.0 + */ + public void setDutyCycle(double output){ + targetDutyCycle = output; + motor.setControl(new DutyCycleOut(output)); + } + /** * Sets the motor's position to a certain value * @param position mechanisam position after taking the position conversion @@ -203,6 +231,14 @@ private void initNT(int canId){ canId + "targetVelocity" ).publish(); + targetTorqueCurrentFOCPublisher = motorStatsTable.getDoubleTopic( + canId + "targetTorqueCurrentFOC" + ).publish(); + + targetDutyCyclePublisher = motorStatsTable.getDoubleTopic( + canId + "targetDutyCycle" + ).publish(); + closedLoopErrorPublisher = motorStatsTable.getDoubleTopic( canId + "closedLoopError" ).publish(); @@ -244,6 +280,14 @@ private void initLogs(int canId){ targetVelocityLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "targetVelocity" ); + + targetTorqueCurrentFOCLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetTorqueCurrentFOC" + ); + + targetDutyCycleLogEntry = new DoubleLogEntry( + DataLogManager.getLog(), canId + "targetDutyCycle" + ); closedLoopErrorLogEntry = new DoubleLogEntry( DataLogManager.getLog(), canId + "closedLoopError" From d3ee1a6fc07ca8fdc4c3b36a2dcf5483579972e8 Mon Sep 17 00:00:00 2001 From: CrolineCrois Date: Wed, 26 Feb 2025 21:58:54 -0800 Subject: [PATCH 46/60] fix build issues --- src/main/java/frc/robot/Constants.java | 3 --- src/main/java/frc/robot/RobotContainer.java | 27 ++++++++++--------- .../Elevator/ElevatorSubsystem.java | 1 + .../Intake/Pivot/PivotSubsystem.java | 2 +- 4 files changed, 17 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index b831dec4..2937f950 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -174,9 +174,6 @@ public static class DebugConstants{ public static final boolean ROLLER_DEBUG = true; } - public static class DebugConstants{ - public static final boolean MASTER_DEBUG = true; - } public static class VisionConstants{ diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e0ee4aa1..2bd5121a 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -63,14 +63,11 @@ public class RobotContainer { VisionConstants.cameraConfigs[3] ); - private Trigger yAxis; - /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); - constructMechController(); bindElevator(); - bindIntake(); + // bindIntake(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -140,15 +137,21 @@ private void constructMechController(){ * Binds elevator commands to mech controller */ private void bindElevator(){ - - mechController.L1().whileTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); - mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); - mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); - mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); - mechController.circle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); - // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); - mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + elevatorSubsystem.setDefaultCommand( + new InstantCommand(() -> { + elevatorSubsystem.setPower(-mechController.getLeftY()); + }, elevatorSubsystem) + ); + + // mechController.L1().whileTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); + // mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); + // mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); + // mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); + // mechController.circle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); + // // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + // mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + } // mechController.L1 //Binds the intake commands to the mech controller private void bindIntake(){ diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java index 55616239..e96b4afd 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -98,6 +98,7 @@ public void setVelocityReference(double velocityReference){ } public void setPower(double power) { + System.out.println(power); motor.setPower(power); } diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 6455d03c..0dd22f38 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -69,7 +69,7 @@ public void periodic(){ if(DebugConstants.MASTER_DEBUG || DebugConstants.PIVOT_DEBUG){ pivotMotor.publishStats(); } - System.out.println(Units.radiansToDegrees(pivotMotor.getPosition())); + // System.out.println(Units.radiansToDegrees(pivotMotor.getPosition())); } public void setPositionReferenceWithVoltage(double position){ From 248ef354a6b2c8afc30a8bc76fec73214f0b9890 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 16:45:47 -0800 Subject: [PATCH 47/60] Publish & Log target duty cycle and torque current foc. --- src/main/java/frc/robot/util/LoggedTalon.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/frc/robot/util/LoggedTalon.java b/src/main/java/frc/robot/util/LoggedTalon.java index 81277739..9aa09781 100644 --- a/src/main/java/frc/robot/util/LoggedTalon.java +++ b/src/main/java/frc/robot/util/LoggedTalon.java @@ -358,6 +358,8 @@ public void publishStats(){ temperaturePublisher.set(motor.getDeviceTemp().getValueAsDouble()); targetPositionPublisher.set(targetPosition); targetVelocityPublisher.set(targetVelocity); + targetDutyCyclePublisher.set(targetDutyCycle); + targetTorqueCurrentFOCPublisher.set(targetTorqueCurrentFOC); closedLoopErrorPublisher.set(motor.getClosedLoopError().getValueAsDouble()); } @@ -393,6 +395,12 @@ public void logStats(){ targetVelocityLogEntry.append(targetVelocity, GRTUtil.getFPGATime()); + targetTorqueCurrentFOCLogEntry.append( + targetTorqueCurrentFOC, GRTUtil.getFPGATime() + ); + + targetDutyCycleLogEntry.append(targetDutyCycle, GRTUtil.getFPGATime()); + closedLoopErrorLogEntry.append( motor.getClosedLoopError().getValueAsDouble(), GRTUtil.getFPGATime() ); From 35fe899e05f608b1d3d856e0f60c5de5989e0329 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 16:48:11 -0800 Subject: [PATCH 48/60] Use logged boolean sensor & allow set duty cycle power --- .../Intake/Roller/RollerSubsystem.java | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java index e04e4ff0..9f2c7659 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Roller/RollerSubsystem.java @@ -10,14 +10,14 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.signals.InvertedValue; -import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.util.LoggedBooleanSensor; import frc.robot.util.LoggedTalon; public class RollerSubsystem extends SubsystemBase{ private LoggedTalon rollerMotor; - private DigitalInput intakeSensor; + private LoggedBooleanSensor intakeSensor; private TalonFXConfiguration rollerConfig = new TalonFXConfiguration() .withSlot0( @@ -45,14 +45,19 @@ public RollerSubsystem(){ rollerMotor = new LoggedTalon( RollerConstants.ROLLER_CAN_ID, RollerConstants.ROLLER_CAN_NAME, rollerConfig ); - intakeSensor = new DigitalInput(1); + + intakeSensor = new LoggedBooleanSensor( + "Intake Distance Sensor", 1 + ); } @Override public void periodic(){ rollerMotor.logStats(); + intakeSensor.logStats(); if(MASTER_DEBUG || ROLLER_DEBUG){ rollerMotor.publishStats(); + intakeSensor.publishStats(); } } @@ -68,6 +73,14 @@ public void setRollerSpeed(double speed){ rollerMotor.setSpeed(speed); } + /** + * Send duty cycle control reuest to roller motors + * @param output + */ + public void setDutyCycle(double output){ + rollerMotor.setDutyCycle(output); + } + public double getClosedLoopError(){ return rollerMotor.getClosedLoopError(); } From 0c64c0eb9682ec900060fc97d75adbf206f9f9cb Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 16:59:20 -0800 Subject: [PATCH 49/60] Tuned Elevator, Intake, Pivot Constants --- src/main/java/frc/robot/Constants.java | 30 ++++++++++++++++++++------ 1 file changed, 23 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 2937f950..87667455 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -30,13 +30,18 @@ public static class OperatorConstants { public static class ElevatorConstants { public static final double dutyCycletoticks = 123.; - public static final double SOURCE_POS= 0.0; //change + public static final double SOURCE_POS = 29.4755; //change public static final double L1_POS = 0.3 * dutyCycletoticks; //change - public static final double L2_POS = 0.5 * dutyCycletoticks; //change - public static final double L3_POS = 0.6 * dutyCycletoticks; //change - public static final double L4_POS = 0.9 * dutyCycletoticks; //change + public static final double L2_POS = 52.014; + // public static final double L2_POS = 0.5 * dutyCycletoticks; //change + public static final double L3_POS = 81.318; + // public static final double L3_POS = 0.6 * dutyCycletoticks; //change + // public static final double L4_POS = 0.9 * dutyCycletoticks; //change + public static final double L4_POS = 126.; public static final double GROUND_POS = 0.0; + public static final double DUTY_CYCLE_TO_GROUND_SPEED = 0.3; + public static final double ELEVATOR_TOLERANCE = 8; //change public static final int MOTOR_ID = 13; //change @@ -45,6 +50,7 @@ public static class ElevatorConstants { public static final double kP = 1; //change public static final double kI = 0; //change public static final double kD = 0; //change + public static final double kS = 0; public static final double arbFF = 30; //chang public static final double FORWARD_LIMIT = 126; //change @@ -59,6 +65,8 @@ public static class ElevatorConstants { public static final double DIST_TO_TICKS = 1. / TICKS_TO_DIST; public static final boolean ELEVATOR_DEBUG = true; + + public static final double CONTROLLER_DEADZONE = 0.1; } public static class IntakeConstans{ @@ -75,8 +83,8 @@ public static class PivotConstants{ public static final double PIVOT_MANUAL_SPEED = 0.15; - public static final double SOURCE_POS = Units.degreesToRadians(45.); - public static final double OUTTAKE_POS = Units.degreesToRadians(-45.); + public static final double SOURCE_POS = 0.9714; + public static final double OUTTAKE_POS = -0.4; public static final double PIVOT_TOLERANCE = 0.1; @@ -88,6 +96,8 @@ public static class PivotConstants{ public static final double PIVOT_RAMP_RATE = 0.03; public static final double PIVOT_CURRENT_LIMIT = 100.; + + public static final double CONTROLLER_DEADZONE = 0.1; } public static class RollerConstants{ @@ -103,10 +113,16 @@ public static class RollerConstants{ public static final double ROLLER_IN_SPEED = 0.5; public static final double ROLLER_OUT_SPEED = -0.5; public static final double ROLLER_OFF_SPEED = 0; + + public static final double ROLLER_DUTY_CYCLE_IN_SPEED = 0.5; + public static final double ROLLER_DUTY_CYCLE_OUT_SPEED = -0.5; + public static final double ROLLER_TOLERANCE = 0.1; public static final double ROLLER_RAMP_RATE = 0.02; public static final double ROLLER_CURRENT_LIMIT = 100.; + + public static final double ROLLER_CONTROLLER_DEADZONE = 0.1; } } @@ -158,7 +174,7 @@ public static class SwerveConstants { public static final double[] STEER_D = new double[] {0, 0, 0, 0}; public static final double[] STEER_FF = new double[] {0.023,.02,0.025,0.03}; //{0.036, 0.024, 0.0182, 0.05}; - public static final boolean DRIVE_DEBUG = false; + public static final boolean DRIVE_DEBUG = true; public static final boolean STEER_DEBUG = false; public static final boolean STATE_DEBUG = false; } From a959bc496d9a4c4ff17e5fb684ce669fa7c3c25f Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:00:14 -0800 Subject: [PATCH 50/60] Disable soft limit, add methods allowing setting duty cycle, torque current, and position --- .../subsystems/Intake/Pivot/PivotSubsystem.java | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java index 0dd22f38..ba12b24b 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Intake/Pivot/PivotSubsystem.java @@ -49,9 +49,9 @@ public class PivotSubsystem extends SubsystemBase{ ) .withSoftwareLimitSwitch( new SoftwareLimitSwitchConfigs() - .withForwardSoftLimitEnable(true) + .withForwardSoftLimitEnable(false) .withForwardSoftLimitThreshold(PivotConstants.PIVOT_MAX_POS) - .withReverseSoftLimitEnable(true) + .withReverseSoftLimitEnable(false) .withReverseSoftLimitThreshold(PivotConstants.PIVOT_MIN_POS) ); @@ -109,4 +109,16 @@ public double getPosition() { public void setPower(double speed) { pivotMotor.setPower(speed); } + + public void setTorqueCurrentFOC(double current){ + pivotMotor.setTorqueCurrentFOC(current); + } + + public void setDutyCycle(double output){ + pivotMotor.setDutyCycle(output); + } + + public void setPosition(double position){ + pivotMotor.setPosition(position); + } } From be2a948cb2bba21a1c8ba37b8e89ad56f89b861b Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:01:23 -0800 Subject: [PATCH 51/60] Use logged limit switch, disable soft limit, allow set duty cycle and torque current --- .../Elevator/ElevatorSubsystem.java | 32 +++++++++++++++---- 1 file changed, 25 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java index e96b4afd..207a28f2 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorSubsystem.java @@ -9,12 +9,14 @@ import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import frc.robot.Constants.DebugConstants; import frc.robot.Constants.ElevatorConstants; import frc.robot.controllers.MechController; +import frc.robot.util.LoggedBooleanSensor; import frc.robot.util.LoggedTalon; /** @@ -28,7 +30,7 @@ public class ElevatorSubsystem extends SubsystemBase { private double arbFF; //limit switch - private final DigitalInput zeroLimitSwitch; + private final LoggedBooleanSensor zeroLimitSwitch; /** * Constructs limit switch and motors. @@ -40,6 +42,7 @@ public ElevatorSubsystem() { .withKP(ElevatorConstants.kP) .withKI(ElevatorConstants.kI) .withKD(ElevatorConstants.kD) + .withKS(ElevatorConstants.kS) ) .withMotorOutput( new MotorOutputConfigs() @@ -48,8 +51,8 @@ public ElevatorSubsystem() { ) .withSoftwareLimitSwitch( new SoftwareLimitSwitchConfigs() - .withReverseSoftLimitEnable(true) - .withForwardSoftLimitEnable(true) + .withReverseSoftLimitEnable(false) + .withForwardSoftLimitEnable(false) .withReverseSoftLimitThreshold(ElevatorConstants.REVERSE_LIMIT) .withForwardSoftLimitThreshold(ElevatorConstants.FORWARD_LIMIT) ) @@ -63,19 +66,23 @@ public ElevatorSubsystem() { ElevatorConstants.MOTOR_ID, "can", motorConfig ); - zeroLimitSwitch = new DigitalInput(ElevatorConstants.LIMIT_ID); + zeroLimitSwitch = new LoggedBooleanSensor( + "Elevator Limit Switch", ElevatorConstants.LIMIT_ID + ); } @Override public void periodic() { if(!zeroLimitSwitch.get()){ motor.setPosition(0); - motor.setPower(0); + // motor.setPower(0); } - System.out.println(motor.getPosition()); + // System.out.println(motor.getPosition()); motor.logStats(); + zeroLimitSwitch.logStats(); if(DebugConstants.MASTER_DEBUG || ElevatorConstants.ELEVATOR_DEBUG) { motor.publishStats(); + zeroLimitSwitch.publishStats(); } } @@ -98,10 +105,17 @@ public void setVelocityReference(double velocityReference){ } public void setPower(double power) { - System.out.println(power); + // System.out.println(power); motor.setPower(power); } + public void setTorqueCurrentFOC(double current){ + motor.setTorqueCurrentFOC(current); + } + + public void setDutyCycle(double output){ + motor.setDutyCycle(output); + } /** * Gets the closed loop error of the motor. * @return closed loop error @@ -109,4 +123,8 @@ public void setPower(double power) { public double getClosedLoopError(){ return motor.getClosedLoopError(); } + + public boolean getLimitSwitch(){ + return zeroLimitSwitch.get(); + } } \ No newline at end of file From 8ea31eb777400d66b9b2dd5b0817a0bd6cdc2f8c Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:01:56 -0800 Subject: [PATCH 52/60] Added command to make rollers run till distance sensor detects --- .../Roller/RollerInTillSensorCommand.java | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 src/main/java/frc/robot/Commands/Intake/Roller/RollerInTillSensorCommand.java diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerInTillSensorCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInTillSensorCommand.java new file mode 100644 index 00000000..52981b3d --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInTillSensorCommand.java @@ -0,0 +1,30 @@ +package frc.robot.Commands.Intake.Roller; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.RollerConstants; +import frc.robot.subsystems.Intake.Roller.RollerSubsystem; + +public class RollerInTillSensorCommand extends Command{ + + private RollerSubsystem rollerSubsystem; + + public RollerInTillSensorCommand(RollerSubsystem rollerSubsystem){ + this.rollerSubsystem = rollerSubsystem; + this.addRequirements(rollerSubsystem); + } + + @Override + public void initialize(){ + rollerSubsystem.setDutyCycle(RollerConstants.ROLLER_DUTY_CYCLE_IN_SPEED); + } + + @Override + public void end(boolean interrupted){ + rollerSubsystem.setDutyCycle(0); + } + + @Override + public boolean isFinished(){ + return rollerSubsystem.getIntakeSensor(); + } +} From b2da615e3056303037005a460353427892deef78 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:02:26 -0800 Subject: [PATCH 53/60] Stop intake command when there is a corral in --- .../java/frc/robot/Commands/Intake/Roller/RollerInCommand.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java index 255aa7e0..81c7902a 100644 --- a/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java +++ b/src/main/java/frc/robot/Commands/Intake/Roller/RollerInCommand.java @@ -21,6 +21,7 @@ public void initialize(){ @Override public boolean isFinished(){ return Math.abs(rollerSubsystem.getClosedLoopError()) - < RollerConstants.ROLLER_TOLERANCE; + < RollerConstants.ROLLER_TOLERANCE + || rollerSubsystem.getIntakeSensor(); } } From eb96cb9dd2cbf8a3ef0a4dc970b8ba75e4db9a8b Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:02:55 -0800 Subject: [PATCH 54/60] Rewrite elevator to limit switch command so it stops by limit switch --- .../Elevator/ElevatorToLimitSwitchCommand.java | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java index d5282fd7..f313bf8d 100644 --- a/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java +++ b/src/main/java/frc/robot/Commands/Elevator/ElevatorToLimitSwitchCommand.java @@ -14,11 +14,18 @@ public ElevatorToLimitSwitchCommand(ElevatorSubsystem elevatorSubsystem) { @Override public void initialize() { - elevatorSubsystem.setPower(-.3); + elevatorSubsystem.setDutyCycle( + ElevatorConstants.DUTY_CYCLE_TO_GROUND_SPEED + ); + } + + @Override + public boolean isFinished(){ + return elevatorSubsystem.getLimitSwitch(); } @Override public void end(boolean interrupted) { - elevatorSubsystem.setPower(0); + elevatorSubsystem.setDutyCycle(0); } } From 25f54bc44fb391a9a3f9df0342908e0912af7f61 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:04:43 -0800 Subject: [PATCH 55/60] Command to zero pivot to 90 degrees --- .../Intake/Pivot/PivotZeroTo90Command.java | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) create mode 100644 src/main/java/frc/robot/Commands/Intake/Pivot/PivotZeroTo90Command.java diff --git a/src/main/java/frc/robot/Commands/Intake/Pivot/PivotZeroTo90Command.java b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotZeroTo90Command.java new file mode 100644 index 00000000..746f70b6 --- /dev/null +++ b/src/main/java/frc/robot/Commands/Intake/Pivot/PivotZeroTo90Command.java @@ -0,0 +1,24 @@ +package frc.robot.Commands.Intake.Pivot; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.subsystems.Intake.Pivot.PivotSubsystem; + +public class PivotZeroTo90Command extends Command{ + private final PivotSubsystem pivotSubsystem; + + public PivotZeroTo90Command(PivotSubsystem pivotSubsystem){ + this.pivotSubsystem = pivotSubsystem; + this.addRequirements(pivotSubsystem); + } + + @Override + public void initialize(){ + pivotSubsystem.setPosition(Math.PI / 2.); + } + + @Override + public boolean isFinished(){ + return true; + } +} \ No newline at end of file From d81aaa4d47812117f937a9a6110db5ad9328495c Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 17:05:47 -0800 Subject: [PATCH 56/60] Bind commands based on Lucca's suggestions --- src/main/java/frc/robot/RobotContainer.java | 169 ++++++++++++++++---- 1 file changed, 135 insertions(+), 34 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 2bd5121a..d2261854 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -5,6 +5,7 @@ package frc.robot; import frc.robot.controllers.PS5DriveController; +import frc.robot.controllers.PS5MechController; import com.pathplanner.lib.commands.PathPlannerAuto; @@ -13,7 +14,9 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.ConditionalCommand; import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; import edu.wpi.first.wpilibj2.command.RunCommand; +import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; @@ -26,10 +29,15 @@ import frc.robot.Commands.Intake.Pivot.PivotToOuttakeCommand; import frc.robot.Commands.Intake.Pivot.PivotToSourceCommand; import frc.robot.Commands.Intake.Pivot.PivotUp90Command; +import frc.robot.Commands.Intake.Pivot.PivotZeroTo90Command; import frc.robot.Commands.Intake.Roller.RollerInCommand; +import frc.robot.Commands.Intake.Roller.RollerInTillSensorCommand; import frc.robot.Commands.Intake.Roller.RollerOutCommand; import frc.robot.Commands.Intake.Roller.RollerStopCommand; +import frc.robot.Constants.ElevatorConstants; import frc.robot.Constants.VisionConstants; +import frc.robot.Constants.IntakeConstans.PivotConstants; +import frc.robot.Constants.IntakeConstans.RollerConstants; import frc.robot.Commands.Elevator.ElevatorToGroundCommand; import frc.robot.Commands.Elevator.ElevatorToL1Command; import frc.robot.Commands.Elevator.ElevatorToL2Command; @@ -46,7 +54,11 @@ public class RobotContainer { private PS5DriveController driveController; - private CommandPS5Controller mechController = new CommandPS5Controller(1); + private CommandPS5Controller mechController; + private Trigger manualElevatorTrigger; + private Trigger manualPivotTrigger; + private Trigger manualRollerInTrigger; + private Trigger manualRollerOutTrigger; private final PivotSubsystem pivotSubsystem = new PivotSubsystem(); private final RollerSubsystem rollerSubsystem = new RollerSubsystem(); @@ -66,8 +78,9 @@ public class RobotContainer { /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { constructDriveController(); + constructMechController(); bindElevator(); - // bindIntake(); + bindIntake(); // startLog(); setVisionDataInterface(); configureBindings(); @@ -138,40 +151,122 @@ private void constructMechController(){ */ private void bindElevator(){ - elevatorSubsystem.setDefaultCommand( - new InstantCommand(() -> { - elevatorSubsystem.setPower(-mechController.getLeftY()); - }, elevatorSubsystem) + // elevatorSubsystem.setDefaultCommand( + // new InstantCommand(() -> { + // elevatorSubsystem.setDutyCycle(-mechController.getLeftY()); + // }, elevatorSubsystem) + // ); + + manualElevatorTrigger = new Trigger( + () -> mechController.getRightY() >= ElevatorConstants.CONTROLLER_DEADZONE ); - - // mechController.L1().whileTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); - // mechController.cross().onTrue(new ElevatorToL1Command(elevatorSubsystem)); - // mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); - // mechController.triangle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); - // mechController.circle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); - // // mechController.L1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); - // mechController.R1().onTrue(new ElevatorToGroundCommand(elevatorSubsystem)); + + manualElevatorTrigger.onTrue( + new InstantCommand( + () -> { + elevatorSubsystem.setDutyCycle(mechController.getRightY()); + }, + elevatorSubsystem + ) + ); + + mechController.R1().onTrue(new ElevatorToLimitSwitchCommand(elevatorSubsystem)); + mechController.triangle().onTrue(new ElevatorToL4Command(elevatorSubsystem)); + mechController.circle().onTrue(new ElevatorToL3Command(elevatorSubsystem)); + mechController.square().onTrue(new ElevatorToL2Command(elevatorSubsystem)); + mechController.cross().onTrue(new ElevatorToSourceCommand(elevatorSubsystem)); } - // mechController.L1 - //Binds the intake commands to the mech controller - private void bindIntake(){ + + private void bindPivot(){ // pivotSubsystem.setDefaultCommand( // new InstantCommand(() -> { - // pivotSubsystem.setPower(mechController.getLeftY()); + // pivotSubsystem.setDutyCycle(mechController.getRightY()); // }, // pivotSubsystem // ) // ); + + manualPivotTrigger = new Trigger( + () -> mechController.getLeftY() >= PivotConstants.CONTROLLER_DEADZONE + ); + + manualPivotTrigger.onTrue( + new InstantCommand( + () -> { + pivotSubsystem.setDutyCycle(mechController.getLeftY()); + }, + pivotSubsystem + ) + ); + + mechController.povDown().onTrue( + new PivotToOuttakeCommand(pivotSubsystem) + ); + + mechController.povLeft().onTrue( + new PivotToHorizontalCommand(pivotSubsystem) + ); + + mechController.povRight().onTrue( + new PivotToSourceCommand(pivotSubsystem) + ); + + mechController.povUp().onTrue( + new ConditionalCommand( + new ParallelCommandGroup( + new ElevatorToGroundCommand(elevatorSubsystem), + new PivotUp90Command(pivotSubsystem) + ), + new SequentialCommandGroup( + new ParallelCommandGroup( + new ElevatorToSourceCommand(elevatorSubsystem), + new PivotToSourceCommand(pivotSubsystem) + ), + new RollerInTillSensorCommand(rollerSubsystem), + new ParallelCommandGroup( + new ElevatorToGroundCommand(elevatorSubsystem), + new PivotUp90Command(pivotSubsystem) + ) + ), + rollerSubsystem::getIntakeSensor + ) + ); + } + + private void bindRollers(){ + manualRollerInTrigger = new Trigger( + () -> + mechController.getL2Axis() + >= RollerConstants.ROLLER_CONTROLLER_DEADZONE + ); + manualRollerOutTrigger = new Trigger( + () -> + mechController.getR2Axis() + >= RollerConstants.ROLLER_CONTROLLER_DEADZONE + ); + + manualRollerInTrigger.onTrue( + new RollerInCommand(rollerSubsystem) + ); - rollerSubsystem.setDefaultCommand(new ConditionalCommand( - new InstantCommand( () -> { - //ps5 trigger's range is -1 to 1, with non-input position being -1. This maps the range -1 to 1 to 0 to 1. - rollerSubsystem.setRollerSpeed(.25 * (mechController.getL2Axis() + 1.) / 2.); - }, rollerSubsystem), - new InstantCommand( () -> { - rollerSubsystem.setRollerSpeed(.15 * (mechController.getL2Axis() - mechController.getR2Axis())); - }, rollerSubsystem), - () -> rollerSubsystem.getIntakeSensor())); + manualRollerOutTrigger.onTrue( + new RollerOutCommand(rollerSubsystem) + ); + } + //Binds the intake commands to the mech controller + private void bindIntake(){ + // mechController.R1().onTrue(new PivotZeroTo90Command(pivotSubsystem)); + bindPivot(); + bindRollers(); + // rollerSubsystem.setDefaultCommand(new ConditionalCommand( + // new InstantCommand( () -> { + // //ps5 trigger's range is -1 to 1, with non-input position being -1. This maps the range -1 to 1 to 0 to 1. + // rollerSubsystem.setRollerSpeed(.25 * (me chController.getL2Axis() + 1.) / 2.); + // }, rollerSubsystem), + // new InstantCommand( () -> { + // rollerSubsystem.setRollerSpeed(.15 * (mechController.getL2Axis() - mechController.getR2Axis())); + // }, rollerSubsystem), + // () -> rollerSubsystem.getIntakeSensor())); // mechController.povUp().onTrue( // new ConditionalCommand( @@ -187,14 +282,20 @@ private void bindIntake(){ // () -> pivotSubsystem.getPosition() > 0 // )); - mechController.povUp().onTrue( - new PivotToSourceCommand(pivotSubsystem) - ); - mechController.L1().onTrue( - new PivotUp90Command(pivotSubsystem) - ); + // mechController.L1().onTrue( + // new PivotUp90Command(pivotSubsystem) + // ); + // mechController.povDown().onTrue( + // new PivotToOuttakeCommand(pivotSubsystem) + // ); + + // mechController.povRight().onTrue( + // new PivotToSourceCommand(pivotSubsystem) + // ); - mechController.povDown().onTrue(new PivotToOuttakeCommand(pivotSubsystem)); + // mechController.povUp().onTrue( + // new PivotToHorizontalCommand(pivotSubsystem) + // ); } /** From bae628be65eed5f2443e3f50291719dcb0c567b5 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 21:54:23 -0800 Subject: [PATCH 57/60] Remove unused PS5 mech controller --- src/main/java/frc/robot/RobotContainer.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d2261854..5c96f01e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -5,7 +5,6 @@ package frc.robot; import frc.robot.controllers.PS5DriveController; -import frc.robot.controllers.PS5MechController; import com.pathplanner.lib.commands.PathPlannerAuto; From c001f3bbd543f341ddfcade2d2250d820e409690 Mon Sep 17 00:00:00 2001 From: Jesse Date: Thu, 27 Feb 2025 22:04:40 -0800 Subject: [PATCH 58/60] Remove unused subsystems --- src/main/java/frc/robot/RobotContainer.java | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 883db6dd..250bddc1 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -74,8 +74,6 @@ public class RobotContainer { private final ElevatorSubsystem elevatorSubsystem = new ElevatorSubsystem(); private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(); - private final FieldManagementSubsystem fieldManagementSubsystem = new FieldManagementSubsystem(); - private final PhoenixLoggingSubsystem phoenixLoggingSubsystem = new PhoenixLoggingSubsystem(fieldManagementSubsystem); //driver camera stuff: private UsbCamera driverCamera; From 95a62b7daff08065d77526a724ceaf121f06bead Mon Sep 17 00:00:00 2001 From: Tony Wu Date: Fri, 28 Feb 2025 09:22:17 -0800 Subject: [PATCH 59/60] changed camera names --- src/main/java/frc/robot/Constants.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index d740dc3c..8f670fba 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -111,16 +111,16 @@ public static class VisionConstants{ }; public static final CameraConfig[] cameraConfigs = new CameraConfig[]{ - new CameraConfig( - "7", + new CameraConfig(//back top cam + "8", new Transform3d( -0.019, -0.071, 0.981, new Rotation3d(0, -Math.PI/6., Math.PI) ), PoseStrategy.LOWEST_AMBIGUITY ), - new CameraConfig( - "3", + new CameraConfig(//front top cam + "0", new Transform3d( 0.031, -0.071,0.981, new Rotation3d(0, -Math.PI * 6., 0) @@ -128,7 +128,7 @@ public static class VisionConstants{ PoseStrategy.LOWEST_AMBIGUITY ), new CameraConfig( - "4", + "6", new Transform3d(//11.3 in above ground 0.235, -0.286, 0.220 , new Rotation3d(0, -Math.PI/9., Math.PI / 9.) @@ -136,7 +136,7 @@ public static class VisionConstants{ PoseStrategy.LOWEST_AMBIGUITY ), new CameraConfig( - "2", + "5", new Transform3d( 0.2921, 0.2921, 0.1651, new Rotation3d(0, -Math.PI / 9., -Math.PI/18) From 20117bf5d6505408f19939da258692647787b9e6 Mon Sep 17 00:00:00 2001 From: Jesse Chu Date: Mon, 17 Mar 2025 14:46:20 -0700 Subject: [PATCH 60/60] 800-600 calibrations --- vision_settings/Camera Calibrations/0-800-600.json | 1 + vision_settings/Camera Calibrations/5-800-600.json | 1 + vision_settings/Camera Calibrations/6-800-600.json | 1 + vision_settings/Camera Calibrations/8-800-600.json | 1 + 4 files changed, 4 insertions(+) create mode 100644 vision_settings/Camera Calibrations/0-800-600.json create mode 100644 vision_settings/Camera Calibrations/5-800-600.json create mode 100644 vision_settings/Camera Calibrations/6-800-600.json create mode 100644 vision_settings/Camera Calibrations/8-800-600.json diff --git a/vision_settings/Camera Calibrations/0-800-600.json b/vision_settings/Camera Calibrations/0-800-600.json new file mode 100644 index 00000000..2cebf94b --- /dev/null +++ b/vision_settings/Camera Calibrations/0-800-600.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[686.5841359313354,0.0,379.4785972279374,0.0,686.7950424886116,324.4180973470417,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04870468935102891,-0.08862788219219972,5.104949460312525E-4,-9.711466049615847E-4,0.0631791693818022,-0.0015647696127629373,0.0034661501663663325,-0.00255362621386482]},"calobjectWarp":[4.8722455342101E-5,7.800714755018637E-5],"observations":[{"locationInObjectSpace":[{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":260.76043701171875,"y":451.91546630859375},{"x":239.5273895263672,"y":386.8372497558594},{"x":217.28829956054688,"y":319.0209655761719},{"x":193.9193572998047,"y":247.47470092773438},{"x":169.3634796142578,"y":172.96524047851562},{"x":324.1816711425781,"y":479.4101867675781},{"x":306.36883544921875,"y":421.122314453125},{"x":287.73907470703125,"y":360.30950927734375},{"x":268.2595520019531,"y":297.3260498046875},{"x":248.1795654296875,"y":230.91876220703125},{"x":226.46327209472656,"y":161.7320556640625},{"x":377.1192321777344,"y":503.2763977050781},{"x":361.7267761230469,"y":449.64166259765625},{"x":345.7608337402344,"y":394.8302917480469},{"x":329.0179748535156,"y":337.79730224609375},{"x":311.9980163574219,"y":278.5247802734375},{"x":293.78424072265625,"y":216.47718811035156},{"x":275.1116027832031,"y":152.10333251953125},{"x":408.6861267089844,"y":474.2207946777344},{"x":394.66412353515625,"y":423.7300109863281},{"x":380.2694091796875,"y":371.78668212890625},{"x":365.2758483886719,"y":317.9227600097656},{"x":350.033447265625,"y":262.1565246582031},{"x":333.9768981933594,"y":204.05027770996094},{"x":317.151611328125,"y":143.62796020507812},{"x":436.666015625,"y":448.5000305175781},{"x":423.66326904296875,"y":400.6343994140625},{"x":410.6938781738281,"y":351.5574951171875},{"x":397.1262512207031,"y":300.4136047363281},{"x":383.1581726074219,"y":247.90419006347656},{"x":368.86285400390625,"y":192.962646484375},{"x":353.8082275390625,"y":136.11624145507812},{"x":461.3290710449219,"y":425.82659912109375},{"x":449.69500732421875,"y":380.172607421875},{"x":437.8064270019531,"y":333.360107421875},{"x":425.36151123046875,"y":285.11083984375},{"x":412.890625,"y":235.16336059570312},{"x":399.8593444824219,"y":183.17405700683594},{"x":386.2677307128906,"y":129.89300537109375},{"x":483.5523681640625,"y":405.6595153808594},{"x":472.85467529296875,"y":361.94146728515625},{"x":461.87103271484375,"y":317.31475830078125},{"x":450.69342041015625,"y":271.25250244140625},{"x":439.327880859375,"y":223.8029022216797},{"x":427.3277587890625,"y":174.56060791015625},{"x":415.07659912109375,"y":123.90824127197266}],"reprojectionErrors":[{"x":-0.35626220703125,"y":-0.145721435546875},{"x":-0.270233154296875,"y":-0.01898193359375},{"x":-0.1336822509765625,"y":-0.13568115234375},{"x":0.10845947265625,"y":0.2816009521484375},{"x":0.4377593994140625,"y":0.23046875},{"x":-0.2569580078125,"y":0.281005859375},{"x":-0.362274169921875,"y":0.17633056640625},{"x":-0.3800048828125,"y":0.171478271484375},{"x":-0.324798583984375,"y":-0.24578857421875},{"x":-0.4976806640625,"y":0.00592041015625},{"x":0.0807952880859375,"y":0.0946502685546875},{"x":-0.168731689453125,"y":-0.2890625},{"x":-0.20904541015625,"y":0.3148193359375},{"x":-0.24658203125,"y":0.084716796875},{"x":-0.111907958984375,"y":-0.053924560546875},{"x":-0.341552734375,"y":-0.212432861328125},{"x":-0.0584716796875,"y":0.0048980712890625},{"x":-0.040740966796875,"y":-0.0024261474609375},{"x":-0.263916015625,"y":-0.065643310546875},{"x":-0.17291259765625,"y":0.163848876953125},{"x":-0.190155029296875,"y":0.0595703125},{"x":-0.116363525390625,"y":-0.00994873046875},{"x":-0.330413818359375,"y":-0.170166015625},{"x":-0.298065185546875,"y":-0.098724365234375},{"x":-0.0982666015625,"y":0.0559844970703125},{"x":-0.3499755859375,"y":0.12164306640625},{"x":-0.010162353515625,"y":0.226654052734375},{"x":-0.113433837890625,"y":-0.054534912109375},{"x":-0.049652099609375,"y":0.0499267578125},{"x":-0.03973388671875,"y":-0.25115966796875},{"x":-0.181549072265625,"y":0.0124664306640625},{"x":-0.069610595703125,"y":0.2101593017578125},{"x":-0.11480712890625,"y":0.02349853515625},{"x":-0.06170654296875,"y":0.184783935546875},{"x":-0.10638427734375,"y":0.067474365234375},{"x":0.035430908203125,"y":-0.121337890625},{"x":-0.185211181640625,"y":-0.1963348388671875},{"x":-0.253875732421875,"y":0.10491943359375},{"x":-0.191925048828125,"y":-0.054534912109375},{"x":0.0269775390625,"y":-0.245452880859375},{"x":0.0755615234375,"y":0.04522705078125},{"x":0.10455322265625,"y":-0.05511474609375},{"x":0.007598876953125,"y":-0.08062744140625},{"x":-0.236602783203125,"y":-0.1445159912109375},{"x":-0.19769287109375,"y":0.0894317626953125},{"x":-0.276580810546875,"y":0.1648712158203125}],"optimisedCameraToObject":{"translation":{"x":-0.037780637856517564,"y":0.12606611594716677,"z":0.24496503293168936},"rotation":{"quaternion":{"W":0.5089071644491748,"X":0.33551460924938065,"Y":-0.27892398075087643,"Z":-0.7420544844650028}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":333.3988342285156,"y":536.5717163085938},{"x":313.3201599121094,"y":476.2336120605469},{"x":292.8981628417969,"y":414.94927978515625},{"x":271.65118408203125,"y":351.6644592285156},{"x":249.98138427734375,"y":286.6240234375},{"x":227.1824493408203,"y":219.2567138671875},{"x":203.80938720703125,"y":149.98245239257812},{"x":381.93231201171875,"y":505.1350402832031},{"x":363.67144775390625,"y":447.81817626953125},{"x":344.8462829589844,"y":389.39727783203125},{"x":326.1302795410156,"y":329.4318542480469},{"x":305.86102294921875,"y":267.8199768066406},{"x":285.61785888671875,"y":204.08551025390625},{"x":264.28228759765625,"y":139.1394805908203},{"x":425.2359924316406,"y":477.2225646972656},{"x":408.31829833984375,"y":422.47955322265625},{"x":391.20367431640625,"y":366.8413391113281},{"x":373.5949401855469,"y":309.515625},{"x":355.4884948730469,"y":251.03121948242188},{"x":336.8930358886719,"y":190.510986328125},{"x":317.78802490234375,"y":128.46902465820312},{"x":464.9458923339844,"y":451.7951354980469},{"x":449.2194519042969,"y":399.475830078125},{"x":433.23388671875,"y":346.39569091796875},{"x":417.0230712890625,"y":291.8290710449219},{"x":400.4862060546875,"y":235.90579223632812},{"x":383.2485656738281,"y":178.19410705566406},{"x":365.8495178222656,"y":119.15557861328125},{"x":500.68988037109375,"y":428.913330078125},{"x":486.0137939453125,"y":378.76953125},{"x":471.1642761230469,"y":327.979736328125},{"x":456.2118225097656,"y":275.6124267578125},{"x":440.96038818359375,"y":222.24842834472656},{"x":425.2649841308594,"y":167.06080627441406},{"x":409.2655334472656,"y":110.8816146850586},{"x":533.4191284179688,"y":408.0117492675781},{"x":519.85009765625,"y":359.90460205078125},{"x":506.1856689453125,"y":311.053955078125},{"x":492.05975341796875,"y":260.89788818359375},{"x":478.05767822265625,"y":209.66946411132812},{"x":463.54736328125,"y":156.9709930419922},{"x":448.73211669921875,"y":103.02108001708984},{"x":563.187744140625,"y":388.8904724121094},{"x":550.5166015625,"y":342.6001281738281},{"x":537.8536376953125,"y":295.5847473144531},{"x":524.971923828125,"y":247.35890197753906},{"x":511.7232666015625,"y":198.1658935546875},{"x":498.3134460449219,"y":147.69000244140625},{"x":484.4857482910156,"y":96.10406494140625}],"reprojectionErrors":[{"x":-0.195556640625,"y":-0.41790771484375},{"x":-0.115753173828125,"y":0.19451904296875},{"x":-0.259185791015625,"y":0.030517578125},{"x":-0.170623779296875,"y":0.063934326171875},{"x":-0.2803955078125,"y":-0.0355224609375},{"x":0.0879364013671875,"y":0.2125244140625},{"x":0.34747314453125,"y":0.2913360595703125},{"x":-0.304290771484375,"y":-0.091064453125},{"x":-0.31378173828125,"y":0.2972412109375},{"x":-0.24627685546875,"y":0.23663330078125},{"x":-0.7967529296875,"y":0.098968505859375},{"x":-0.325653076171875,"y":-0.08660888671875},{"x":-0.436614990234375,"y":0.07891845703125},{"x":-0.03680419921875,"y":-0.397369384765625},{"x":-0.049652099609375,"y":-0.14617919921875},{"x":0.086822509765625,"y":0.217803955078125},{"x":-0.0023193359375,"y":0.06982421875},{"x":-0.037628173828125,"y":0.143035888671875},{"x":-0.034332275390625,"y":-0.153839111328125},{"x":-0.020965576171875,"y":-0.0097198486328125},{"x":0.001922607421875,"y":-0.0086517333984375},{"x":-0.36273193359375,"y":6.7138671875E-4},{"x":-0.124114990234375,"y":0.273712158203125},{"x":0.004547119140625,"y":0.026519775390625},{"x":-0.025390625,"y":-0.0665283203125},{"x":-0.1287841796875,"y":-0.18939208984375},{"x":0.052642822265625,"y":0.0326690673828125},{"x":-0.037872314453125,"y":0.07790374755859375},{"x":-0.296295166015625,"y":-0.08233642578125},{"x":0.023590087890625,"y":0.157196044921875},{"x":0.1923828125,"y":-0.128509521484375},{"x":0.127197265625,"y":-0.052703857421875},{"x":0.010955810546875,"y":-0.2434539794921875},{"x":-0.025146484375,"y":0.07666015625},{"x":-0.135528564453125,"y":0.0233154296875},{"x":-0.32769775390625,"y":-0.13580322265625},{"x":-0.11822509765625,"y":0.04046630859375},{"x":-0.100372314453125,"y":-0.11474609375},{"x":0.0814208984375,"y":-0.078948974609375},{"x":-0.169281005859375,"y":-0.126556396484375},{"x":-0.23199462890625,"y":0.096710205078125},{"x":-0.322235107421875,"y":0.3266448974609375},{"x":-0.1171875,"y":-0.21405029296875},{"x":0.07745361328125,"y":-0.03094482421875},{"x":0.00872802734375,"y":-0.113006591796875},{"x":-0.10546875,"y":-0.0096588134765625},{"x":-0.126434326171875,"y":-7.01904296875E-4},{"x":-0.269805908203125,"y":0.191375732421875},{"x":-0.2891845703125,"y":0.35364532470703125}],"optimisedCameraToObject":{"translation":{"x":-0.029396716028898165,"y":0.11432501232287659,"z":0.2553210661456864},"rotation":{"quaternion":{"W":0.5439650368647593,"X":0.24198136135184015,"Y":-0.2093315960880474,"Z":-0.7757108625681748}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":283.6717529296875,"y":486.0821838378906},{"x":263.21051025390625,"y":422.4655456542969},{"x":242.230712890625,"y":358.2789611816406},{"x":221.19992065429688,"y":293.9434509277344},{"x":199.84046936035156,"y":228.62026977539062},{"x":178.2203369140625,"y":163.2427520751953},{"x":343.4911193847656,"y":460.938232421875},{"x":323.7369079589844,"y":399.7220764160156},{"x":304.075927734375,"y":338.1517639160156},{"x":283.9007263183594,"y":276.37591552734375},{"x":263.8378601074219,"y":213.76678466796875},{"x":243.40274047851562,"y":151.2720947265625},{"x":417.06591796875,"y":496.8992919921875},{"x":398.2279357910156,"y":437.7496337890625},{"x":379.4952087402344,"y":378.91400146484375},{"x":360.3835754394531,"y":319.63702392578125},{"x":341.47625732421875,"y":259.9866027832031},{"x":322.3841552734375,"y":199.61126708984375},{"x":302.91656494140625,"y":139.13107299804688},{"x":467.4462890625,"y":473.226806640625},{"x":449.2744140625,"y":416.2776184082031},{"x":431.48516845703125,"y":359.4830017089844},{"x":413.3382873535156,"y":302.3151550292969},{"x":395.29058837890625,"y":244.8965301513672},{"x":376.9793395996094,"y":186.66392517089844},{"x":358.5086364746094,"y":128.11520385742188},{"x":514.2390747070312,"y":451.52899169921875},{"x":496.7814025878906,"y":396.40704345703125},{"x":479.3775939941406,"y":341.7709655761719},{"x":462.2579040527344,"y":286.2433166503906},{"x":445.01617431640625,"y":230.81112670898438},{"x":427.51690673828125,"y":174.5646514892578},{"x":409.7301025390625,"y":117.9370346069336},{"x":558.24169921875,"y":431.1101989746094},{"x":541.3876953125,"y":377.9861755371094},{"x":524.9290161132812,"y":324.8237609863281},{"x":508.3575439453125,"y":271.1887512207031},{"x":491.8123779296875,"y":217.43963623046875},{"x":475.06512451171875,"y":163.0260772705078},{"x":458.2857971191406,"y":108.66548919677734},{"x":599.1641845703125,"y":412.0760498046875},{"x":583.0999145507812,"y":360.5494689941406},{"x":567.0931396484375,"y":309.0162353515625},{"x":551.1766357421875,"y":257.1221618652344},{"x":535.1728515625,"y":204.99925231933594},{"x":519.2310180664062,"y":152.2546844482422},{"x":503.2304992675781,"y":99.35477447509766}],"reprojectionErrors":[{"x":-0.00677490234375,"y":-0.068603515625},{"x":-0.2523193359375,"y":-0.039764404296875},{"x":-0.116119384765625,"y":0.123779296875},{"x":-0.0688934326171875,"y":-0.0089111328125},{"x":0.163787841796875,"y":0.3907318115234375},{"x":0.5106048583984375,"y":0.379058837890625},{"x":-0.363128662109375,"y":0.145111083984375},{"x":-0.31988525390625,"y":0.152679443359375},{"x":-0.4931640625,"y":0.11114501953125},{"x":-0.2783203125,"y":-0.137176513671875},{"x":-0.30487060546875,"y":0.026275634765625},{"x":-0.0911102294921875,"y":-0.355621337890625},{"x":-0.18353271484375,"y":-0.25604248046875},{"x":-0.040557861328125,"y":0.257049560546875},{"x":-0.111846923828125,"y":0.08941650390625},{"x":0.0843505859375,"y":-0.011627197265625},{"x":-0.037841796875,"y":-0.122283935546875},{"x":-0.091827392578125,"y":0.1006011962890625},{"x":0.110382080078125,"y":0.028350830078125},{"x":-0.24810791015625,"y":-0.033233642578125},{"x":0.0478515625,"y":0.3043212890625},{"x":-0.13763427734375,"y":0.14544677734375},{"x":-0.066558837890625,"y":0.010589599609375},{"x":-0.198089599609375,"y":-0.230316162109375},{"x":-0.171783447265625,"y":-0.0217132568359375},{"x":-0.0941162109375,"y":0.13067626953125},{"x":-0.1702880859375,"y":-0.1695556640625},{"x":0.1634521484375,"y":0.22857666015625},{"x":0.353424072265625,"y":-0.178680419921875},{"x":0.167388916015625,"y":-0.020660400390625},{"x":0.009368896484375,"y":-0.291351318359375},{"x":0.01275634765625,"y":-0.0880279541015625},{"x":0.205413818359375,"y":0.14890289306640625},{"x":-0.3988037109375,"y":-0.132720947265625},{"x":0.0238037109375,"y":0.03155517578125},{"x":-0.0308837890625,"y":-0.065093994140625},{"x":-0.056488037109375,"y":0.00531005859375},{"x":-0.194122314453125,"y":-0.122222900390625},{"x":-0.21728515625,"y":0.096221923828125},{"x":-0.29791259765625,"y":-0.0634613037109375},{"x":-0.3406982421875,"y":-0.17059326171875},{"x":-0.0679931640625,"y":0.048431396484375},{"x":0.07232666015625,"y":-0.006927490234375},{"x":0.04583740234375,"y":0.01171875},{"x":0.0283203125,"y":-0.0335540771484375},{"x":-0.131103515625,"y":0.244049072265625},{"x":-0.313720703125,"y":0.3720855712890625}],"optimisedCameraToObject":{"translation":{"x":-0.04283956800982344,"y":0.11690000695482156,"z":0.2512335131767899},"rotation":{"quaternion":{"W":0.574256455806246,"X":0.1375473054380257,"Y":-0.15904770331943882,"Z":-0.791210521795811}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":335.6786804199219,"y":463.9662170410156},{"x":318.5072021484375,"y":407.963134765625},{"x":301.2984619140625,"y":353.07745361328125},{"x":284.1328430175781,"y":298.06396484375},{"x":267.2101135253906,"y":243.37107849121094},{"x":250.02200317382812,"y":188.54063415527344},{"x":233.0713348388672,"y":134.23866271972656},{"x":391.1220703125,"y":446.27508544921875},{"x":373.75006103515625,"y":390.68560791015625},{"x":356.6801452636719,"y":335.8021240234375},{"x":339.3706970214844,"y":280.8540954589844},{"x":322.404296875,"y":226.37777709960938},{"x":305.07720947265625,"y":171.59375},{"x":288.2070617675781,"y":117.39229583740234},{"x":446.0892639160156,"y":428.8354797363281},{"x":428.79632568359375,"y":373.2015686035156},{"x":411.1797790527344,"y":318.4090576171875},{"x":393.9375305175781,"y":263.8677978515625},{"x":376.593017578125,"y":209.4716796875},{"x":359.5020751953125,"y":155.23265075683594},{"x":342.2217102050781,"y":100.88236236572266},{"x":501.2876892089844,"y":411.3037109375},{"x":483.6300964355469,"y":356.0844421386719},{"x":466.0395812988281,"y":301.1211242675781},{"x":448.8399963378906,"y":246.6822509765625},{"x":431.51251220703125,"y":192.3066864013672},{"x":414.2789611816406,"y":137.98890686035156},{"x":397.0897216796875,"y":84.0212631225586},{"x":556.0267944335938,"y":393.97650146484375},{"x":538.1721801757812,"y":338.6131896972656},{"x":520.4246826171875,"y":284.1025695800781},{"x":503.0810852050781,"y":229.66038513183594},{"x":485.45330810546875,"y":175.46295166015625},{"x":468.603759765625,"y":120.94713592529297},{"x":451.3589782714844,"y":67.23190307617188},{"x":611.2814331054688,"y":376.6547546386719},{"x":592.8902587890625,"y":321.34771728515625},{"x":575.5552978515625,"y":266.7723693847656},{"x":557.5867309570312,"y":212.4526824951172},{"x":540.2703857421875,"y":158.53457641601562},{"x":523.1068115234375,"y":104.06712341308594},{"x":665.8716430664062,"y":359.3691101074219},{"x":647.846435546875,"y":304.214111328125},{"x":629.73974609375,"y":249.9288330078125},{"x":612.1669311523438,"y":195.44119262695312},{"x":594.544921875,"y":141.1785888671875},{"x":577.0029907226562,"y":87.09271240234375}],"reprojectionErrors":[{"x":0.05078125,"y":-0.215484619140625},{"x":-0.0233154296875,"y":0.31170654296875},{"x":0.0172119140625,"y":-0.023162841796875},{"x":0.090087890625,"y":0.01910400390625},{"x":-0.006317138671875,"y":-0.0159759521484375},{"x":0.2344818115234375,"y":0.32391357421875},{"x":0.3078460693359375,"y":0.366912841796875},{"x":-0.120025634765625,"y":-0.050048828125},{"x":-0.099456787109375,"y":0.172637939453125},{"x":-0.30181884765625,"y":-0.05657958984375},{"x":-0.18731689453125,"y":0.02679443359375},{"x":-0.3404541015625,"y":-0.1194915771484375},{"x":-0.059326171875,"y":0.27813720703125},{"x":-0.163330078125,"y":0.3236083984375},{"x":0.051177978515625,"y":-0.089111328125},{"x":-0.113372802734375,"y":0.284423828125},{"x":0.126708984375,"y":0.069366455078125},{"x":0.071624755859375,"y":-0.15008544921875},{"x":0.196014404296875,"y":-0.2738494873046875},{"x":0.142181396484375,"y":-0.3196563720703125},{"x":0.351348876953125,"y":-0.0249481201171875},{"x":-0.1356201171875,"y":0.0086669921875},{"x":-0.041717529296875,"y":0.071258544921875},{"x":0.06793212890625,"y":0.1295166015625},{"x":-0.132415771484375,"y":-0.0910186767578125},{"x":-0.1258544921875,"y":-0.13519287109375},{"x":-0.136077880859375,"y":-0.003265380859375},{"x":-0.11529541015625,"y":0.00665283203125},{"x":0.017578125,"y":-0.05584716796875},{"x":0.20208740234375,"y":0.251861572265625},{"x":0.36407470703125,"y":-0.042694091796875},{"x":0.204925537109375,"y":-0.1612091064453125},{"x":0.4107666015625,"y":-0.28594970703125},{"x":-0.082733154296875,"y":0.14044952392578125},{"x":-0.103912353515625,"y":-0.00670623779296875},{"x":-0.45672607421875,"y":-0.085845947265625},{"x":0.15753173828125,"y":0.2640380859375},{"x":-0.19781494140625,"y":0.131500244140625},{"x":0.1649169921875,"y":-0.013397216796875},{"x":-0.0419921875,"y":-0.32244873046875},{"x":-0.3209228515625,"y":0.14951324462890625},{"x":-0.3714599609375,"y":-0.11431884765625},{"x":-0.2301025390625,"y":0.17938232421875},{"x":0.0810546875,"y":-0.1485137939453125},{"x":-0.0552978515625,"y":-0.0318603515625},{"x":-0.05810546875,"y":0.0960845947265625},{"x":-0.0584716796875,"y":0.27789306640625}],"optimisedCameraToObject":{"translation":{"x":-0.035783130902599845,"y":0.09287585089578954,"z":0.2998080920635342},"rotation":{"quaternion":{"W":0.5915762062693766,"X":-0.006718557623367221,"Y":-0.013447683877060964,"Z":-0.8061089336793981}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":139.305419921875,"y":519.8233032226562},{"x":143.43711853027344,"y":463.2253112792969},{"x":147.13327026367188,"y":409.39544677734375},{"x":151.00706481933594,"y":358.2430419921875},{"x":154.4467010498047,"y":309.1539001464844},{"x":195.52818298339844,"y":517.5656127929688},{"x":198.3333740234375,"y":461.4156188964844},{"x":201.0423126220703,"y":407.7847595214844},{"x":203.23883056640625,"y":356.4863586425781},{"x":205.5159912109375,"y":307.99822998046875},{"x":250.76568603515625,"y":516.1307373046875},{"x":252.2374267578125,"y":459.85107421875},{"x":253.39955139160156,"y":406.2758483886719},{"x":254.88870239257812,"y":355.3564453125},{"x":256.23455810546875,"y":306.7854309082031},{"x":306.19952392578125,"y":514.0025024414062},{"x":306.33306884765625,"y":458.2638244628906},{"x":306.78997802734375,"y":404.73907470703125},{"x":306.7585144042969,"y":353.9786071777344},{"x":306.6789855957031,"y":305.51312255859375},{"x":360.8890380859375,"y":512.2780151367188},{"x":359.86273193359375,"y":456.7904357910156},{"x":358.50726318359375,"y":403.0931091308594},{"x":357.876220703125,"y":352.7110290527344},{"x":356.8764953613281,"y":304.1683044433594},{"x":416.0281066894531,"y":511.1210632324219},{"x":413.5573425292969,"y":454.9210510253906},{"x":411.52294921875,"y":401.8966064453125},{"x":409.13494873046875,"y":351.2457580566406},{"x":406.8581848144531,"y":303.1268005371094},{"x":470.73583984375,"y":509.31085205078125},{"x":466.7646179199219,"y":453.83978271484375},{"x":463.1189270019531,"y":400.26080322265625},{"x":459.9564208984375,"y":349.9531555175781},{"x":456.81341552734375,"y":301.473388671875}],"reprojectionErrors":[{"x":0.4109039306640625,"y":-0.61541748046875},{"x":0.2567138671875,"y":-0.2060546875},{"x":0.350921630859375,"y":0.0035400390625},{"x":0.0931396484375,"y":-0.07171630859375},{"x":0.106842041015625,"y":0.022216796875},{"x":-0.133697509765625,"y":-0.0765380859375},{"x":-0.2698822021484375,"y":0.0230712890625},{"x":-0.435638427734375,"y":0.161163330078125},{"x":-0.2062225341796875,"y":0.349700927734375},{"x":-0.1668548583984375,"y":-0.04840087890625},{"x":0.103759765625,"y":-0.355224609375},{"x":0.0018768310546875,"y":0.00958251953125},{"x":0.1444549560546875,"y":0.21710205078125},{"x":-0.1007232666015625,"y":0.1422119140625},{"x":-0.259246826171875,"y":-0.0660400390625},{"x":-0.0509033203125,"y":0.06451416015625},{"x":-0.104736328125,"y":0.021148681640625},{"x":-0.487060546875,"y":0.30084228515625},{"x":-0.3857421875,"y":0.180389404296875},{"x":-0.240814208984375,"y":-0.0284423828125},{"x":0.35040283203125,"y":0.08526611328125},{"x":0.174835205078125,"y":-0.0789794921875},{"x":0.382843017578125,"y":0.4935302734375},{"x":-0.082916259765625,"y":0.10589599609375},{"x":-0.1326904296875,"y":0.077301025390625},{"x":0.1209716796875,"y":-0.456939697265625},{"x":0.116607666015625,"y":0.2188720703125},{"x":-0.210845947265625,"y":0.23638916015625},{"x":-0.079071044921875,"y":0.2265625},{"x":0.040008544921875,"y":-0.124725341796875},{"x":0.14892578125,"y":-0.341522216796875},{"x":0.379669189453125,"y":-0.26959228515625},{"x":0.45654296875,"y":0.417999267578125},{"x":0.210235595703125,"y":0.171905517578125},{"x":0.093841552734375,"y":0.280548095703125}],"optimisedCameraToObject":{"translation":{"x":-0.13304680001575475,"y":0.16264384720648456,"z":0.29163075807131095},"rotation":{"quaternion":{"W":0.689056254062778,"X":-0.1003306793072028,"Y":-0.11250682023615662,"Z":-0.7088564374590082}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":425.71490478515625,"y":505.2520446777344},{"x":425.751708984375,"y":462.9440002441406},{"x":426.3291931152344,"y":263.39166259765625},{"x":465.8293762207031,"y":507.9552307128906},{"x":465.6510009765625,"y":464.27838134765625},{"x":465.4051208496094,"y":421.9698181152344},{"x":465.10308837890625,"y":380.38006591796875},{"x":464.8750915527344,"y":339.44451904296875},{"x":464.7415466308594,"y":299.3846130371094},{"x":464.3136901855469,"y":260.2457580566406},{"x":507.86090087890625,"y":510.0688171386719},{"x":507.3663330078125,"y":465.89068603515625},{"x":506.2919616699219,"y":422.21429443359375},{"x":505.7340087890625,"y":379.7286376953125},{"x":505.36907958984375,"y":338.274658203125},{"x":504.45068359375,"y":297.00201416015625},{"x":504.1360778808594,"y":256.7260437011719},{"x":552.4892578125,"y":512.9649658203125},{"x":551.179443359375,"y":467.232421875},{"x":550.1832275390625,"y":422.9914855957031},{"x":548.9954833984375,"y":379.2464904785156},{"x":547.9344482421875,"y":336.5090637207031},{"x":547.056640625,"y":294.30462646484375},{"x":546.0301513671875,"y":253.2654571533203},{"x":599.1104125976562,"y":515.9742431640625},{"x":597.292724609375,"y":469.21875},{"x":595.56640625,"y":423.2359619140625},{"x":593.9697265625,"y":378.78826904296875},{"x":592.5799560546875,"y":334.826171875},{"x":591.1188354492188,"y":291.7228698730469},{"x":589.7703857421875,"y":249.26321411132812},{"x":648.337646484375,"y":518.9309692382812},{"x":646.0565795898438,"y":470.62054443359375},{"x":643.8568115234375,"y":424.1692810058594},{"x":641.5667114257812,"y":377.989501953125},{"x":639.8153686523438,"y":332.87640380859375},{"x":638.0227661132812,"y":288.7989807128906},{"x":635.9862060546875,"y":245.48329162597656},{"x":700.1074829101562,"y":522.167236328125},{"x":697.0130004882812,"y":473.11566162109375},{"x":694.4454956054688,"y":424.61749267578125},{"x":691.6255493164062,"y":377.8248596191406},{"x":689.1806030273438,"y":331.0672302246094},{"x":686.8892211914062,"y":285.4613037109375},{"x":684.2967529296875,"y":241.048583984375}],"reprojectionErrors":[{"x":-0.03460693359375,"y":0.375457763671875},{"x":0.07818603515625,"y":0.4495849609375},{"x":0.149688720703125,"y":-0.323883056640625},{"x":0.041229248046875,"y":0.0506591796875},{"x":0.00341796875,"y":0.4737548828125},{"x":0.033447265625,"y":0.3160400390625},{"x":0.119964599609375,"y":0.20355224609375},{"x":0.13275146484375,"y":0.178375244140625},{"x":0.051361083984375,"y":-0.00262451171875},{"x":0.264556884765625,"y":-0.40570068359375},{"x":0.1590576171875,"y":0.433929443359375},{"x":0.035491943359375,"y":0.286712646484375},{"x":0.500335693359375,"y":0.464141845703125},{"x":0.457061767578125,"y":0.2520751953125},{"x":0.228790283203125,"y":-0.214569091796875},{"x":0.56182861328125,"y":-0.108612060546875},{"x":0.298614501953125,"y":-0.267730712890625},{"x":-0.20977783203125,"y":0.1622314453125},{"x":0.03961181640625,"y":0.44207763671875},{"x":-0.00653076171875,"y":0.09857177734375},{"x":0.15631103515625,"y":0.10040283203125},{"x":0.2093505859375,"y":-0.089935302734375},{"x":0.0955810546875,"y":-0.02276611328125},{"x":0.1463623046875,"y":-0.35418701171875},{"x":-0.29412841796875,"y":-0.0848388671875},{"x":-0.02423095703125,"y":0.0302734375},{"x":0.18316650390625,"y":0.286224365234375},{"x":0.28887939453125,"y":-0.10845947265625},{"x":0.2147216796875,"y":-0.132171630859375},{"x":0.2381591796875,"y":-0.184722900390625},{"x":0.17437744140625,"y":-0.0766448974609375},{"x":-0.522216796875,"y":-0.1304931640625},{"x":-0.326904296875,"y":0.286712646484375},{"x":-0.171630859375,"y":-0.19281005859375},{"x":0.11407470703125,"y":-0.0126953125},{"x":-0.100341796875,"y":0.001800537109375},{"x":-0.2359619140625,"y":-0.14697265625},{"x":-0.09130859375,"y":-0.2126922607421875},{"x":-0.6246337890625,"y":-0.29437255859375},{"x":-0.21087646484375,"y":-0.459564208984375},{"x":-0.268310546875,"y":-0.1627197265625},{"x":-0.01947021484375,"y":-0.58984375},{"x":-0.093505859375,"y":-0.102783203125},{"x":-0.270751953125,"y":0.150787353515625},{"x":-0.09808349609375,"y":0.0997467041015625}],"optimisedCameraToObject":{"translation":{"x":0.00456144390902963,"y":0.1373165968310782,"z":0.42684595866969266},"rotation":{"quaternion":{"W":0.6851073886925956,"X":-0.19333213507323888,"Y":0.08752081100007018,"Z":-0.6968433533791691}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":389.68072509765625,"y":443.9480895996094},{"x":388.9791564941406,"y":405.00262451171875},{"x":388.17279052734375,"y":366.3664245605469},{"x":387.3779296875,"y":328.08038330078125},{"x":386.68096923828125,"y":290.1872863769531},{"x":385.73486328125,"y":252.76779174804688},{"x":385.1052551269531,"y":215.3899688720703},{"x":425.64129638671875,"y":445.3201904296875},{"x":424.7464599609375,"y":404.8106994628906},{"x":423.61846923828125,"y":365.28814697265625},{"x":422.68572998046875,"y":325.93505859375},{"x":421.5146484375,"y":287.4656677246094},{"x":420.9818115234375,"y":248.78099060058594},{"x":419.59307861328125,"y":210.76620483398438},{"x":463.3870544433594,"y":446.1947326660156},{"x":462.16595458984375,"y":404.8990478515625},{"x":460.93609619140625,"y":364.2646179199219},{"x":459.5997314453125,"y":323.9466552734375},{"x":458.39642333984375,"y":283.9290771484375},{"x":457.296142578125,"y":244.291748046875},{"x":456.107177734375,"y":205.2392578125},{"x":503.3869323730469,"y":447.28155517578125},{"x":501.525634765625,"y":404.4253845214844},{"x":500.2174072265625,"y":363.0947265625},{"x":498.7848815917969,"y":321.5396423339844},{"x":497.4859924316406,"y":280.3566589355469},{"x":496.0900573730469,"y":240.02720642089844},{"x":494.79644775390625,"y":199.96450805664062},{"x":545.353271484375,"y":448.3727722167969},{"x":543.406005859375,"y":404.8096618652344},{"x":541.4594116210938,"y":361.4754943847656},{"x":540.1829833984375,"y":319.1351013183594},{"x":538.654541015625,"y":277.14349365234375},{"x":536.5684204101562,"y":235.31863403320312},{"x":535.233154296875,"y":194.01295471191406},{"x":590.2550659179688,"y":449.6434326171875},{"x":587.9596557617188,"y":404.5126647949219},{"x":586.0814819335938,"y":360.4283447265625},{"x":583.6536865234375,"y":316.3968505859375},{"x":581.9238891601562,"y":273.4491271972656},{"x":580.1033325195312,"y":230.07199096679688},{"x":578.1494140625,"y":188.14414978027344},{"x":637.3276977539062,"y":451.09576416015625},{"x":635.0610961914062,"y":404.7773132324219},{"x":632.7597045898438,"y":359.07000732421875},{"x":630.3328857421875,"y":314.1390686035156},{"x":627.9649047851562,"y":268.9627380371094},{"x":625.8939208984375,"y":225.05929565429688},{"x":623.6104125976562,"y":180.86666870117188}],"reprojectionErrors":[{"x":0.1412353515625,"y":0.490631103515625},{"x":0.0537109375,"y":0.316009521484375},{"x":0.073272705078125,"y":0.20733642578125},{"x":0.083526611328125,"y":0.1165771484375},{"x":-0.00201416015625,"y":-0.00604248046875},{"x":0.1636962890625,"y":-0.2480010986328125},{"x":0.014892578125,"y":-0.184051513671875},{"x":0.0411376953125,"y":0.0213623046875},{"x":-0.05084228515625,"y":0.394561767578125},{"x":0.09515380859375,"y":0.175689697265625},{"x":0.05059814453125,"y":0.174591064453125},{"x":0.2490234375,"y":-0.330535888671875},{"x":-0.186309814453125,"y":-0.2480010986328125},{"x":0.238616943359375,"y":-0.4701080322265625},{"x":0.062652587890625,"y":0.09967041015625},{"x":0.078948974609375,"y":0.187591552734375},{"x":0.111785888671875,"y":0.030364990234375},{"x":0.25872802734375,"y":-0.035430908203125},{"x":0.280029296875,"y":-0.0018310546875},{"x":0.205596923828125,"y":0.0435028076171875},{"x":0.226959228515625,"y":-0.1116943359375},{"x":-0.10308837890625,"y":0.01995849609375},{"x":0.312713623046875,"y":0.53692626953125},{"x":0.18658447265625,"y":-0.032440185546875},{"x":0.195648193359375,"y":0.0528564453125},{"x":0.081787109375,"y":0.18768310546875},{"x":0.07537841796875,"y":-0.1178741455078125},{"x":-0.023101806640625,"y":-0.2852783203125},{"x":0.01007080078125,"y":-0.005218505859375},{"x":0.24554443359375,"y":0.02215576171875},{"x":0.495361328125,"y":0.284759521484375},{"x":0.08966064453125,"y":0.008209228515625},{"x":-0.049560546875,"y":-0.171905517578125},{"x":0.3829345703125,"y":-0.0826263427734375},{"x":0.078369140625,"y":-0.08526611328125},{"x":-0.36712646484375,"y":-0.14569091796875},{"x":-0.07879638671875,"y":0.181915283203125},{"x":-0.188232421875,"y":-0.045501708984375},{"x":0.27099609375,"y":0.15533447265625},{"x":0.0509033203125,"y":-0.25665283203125},{"x":-0.0601806640625,"y":0.221893310546875},{"x":-0.02001953125,"y":-0.29730224609375},{"x":-0.24603271484375,"y":-0.397796630859375},{"x":-0.314697265625,"y":-0.22735595703125},{"x":-0.32391357421875,"y":-0.146820068359375},{"x":-0.18359375,"y":-0.33270263671875},{"x":-0.07855224609375,"y":0.22576904296875},{"x":-0.2474365234375,"y":-2.899169921875E-4},{"x":-0.18121337890625,"y":0.540802001953125}],"optimisedCameraToObject":{"translation":{"x":-0.015435156641634765,"y":0.10512494669956228,"z":0.4578761165649323},"rotation":{"quaternion":{"W":0.6735637469548609,"X":-0.1913497065021453,"Y":0.1359909767244336,"Z":-0.7008592033063457}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":288.464111328125,"y":453.45306396484375},{"x":292.3011779785156,"y":420.96234130859375},{"x":296.3643493652344,"y":389.1260681152344},{"x":299.8190002441406,"y":358.0668640136719},{"x":303.6895446777344,"y":327.03375244140625},{"x":314.3234558105469,"y":456.0393981933594},{"x":318.3052978515625,"y":422.5594177246094},{"x":321.72552490234375,"y":389.90216064453125},{"x":325.3466491699219,"y":357.7137451171875},{"x":328.91168212890625,"y":326.27813720703125},{"x":341.77374267578125,"y":458.6502685546875},{"x":345.0532531738281,"y":424.0878601074219},{"x":348.5549621582031,"y":390.5503234863281},{"x":370.0015563964844,"y":461.2367248535156},{"x":373.3687438964844,"y":425.8898010253906},{"x":376.3803405761719,"y":391.69793701171875},{"x":400.38043212890625,"y":464.0993957519531},{"x":403.21142578125,"y":427.51531982421875},{"x":406.497802734375,"y":392.59332275390625},{"x":409.1109313964844,"y":357.40185546875},{"x":411.8880615234375,"y":323.2428894042969},{"x":414.9543151855469,"y":290.3634338378906},{"x":432.24066162109375,"y":466.9537353515625},{"x":435.2430725097656,"y":429.4995422363281},{"x":437.78961181640625,"y":393.3033447265625},{"x":440.5290222167969,"y":357.6305847167969},{"x":443.0818176269531,"y":322.8099365234375},{"x":445.5339660644531,"y":288.7939758300781},{"x":448.2059631347656,"y":255.00167846679688},{"x":468.449462890625,"y":431.37872314453125},{"x":470.8722839355469,"y":394.1435241699219},{"x":473.08941650390625,"y":357.5423583984375},{"x":475.5921936035156,"y":321.7387390136719},{"x":477.706298828125,"y":286.7018127441406},{"x":480.201416015625,"y":252.0704345703125}],"reprojectionErrors":[{"x":0.33245849609375,"y":0.02825927734375},{"x":0.291412353515625,"y":0.086151123046875},{"x":-0.051422119140625,"y":0.08197021484375},{"x":0.1407470703125,"y":-0.124053955078125},{"x":-0.15435791015625,"y":0.202423095703125},{"x":0.2293701171875,"y":-0.1646728515625},{"x":-0.104248046875,"y":0.03790283203125},{"x":0.04925537109375,"y":0.040924072265625},{"x":-0.0704345703125,"y":0.1796875},{"x":-0.2042236328125,"y":0.152435302734375},{"x":-0.121917724609375,"y":-0.257415771484375},{"x":0.078338623046875,"y":0.137237548828125},{"x":-0.01641845703125,"y":0.163360595703125},{"x":0.202423095703125,"y":-0.190765380859375},{"x":0.123138427734375,"y":0.04840087890625},{"x":0.32879638671875,"y":-0.175201416015625},{"x":-0.048248291015625,"y":-0.25390625},{"x":0.19012451171875,"y":0.22845458984375},{"x":-0.0946044921875,"y":-0.219940185546875},{"x":0.22833251953125,"y":0.309112548828125},{"x":0.32379150390625,"y":0.49114990234375},{"x":0.068634033203125,"y":0.0577392578125},{"x":-0.067169189453125,"y":-0.14959716796875},{"x":-0.249114990234375,"y":0.150238037109375},{"x":-0.039154052734375,"y":-0.03411865234375},{"x":-0.083984375,"y":0.0064697265625},{"x":-0.002105712890625,"y":-0.080963134765625},{"x":0.1224365234375,"y":-0.272247314453125},{"x":-0.02899169921875,"y":-0.0087127685546875},{"x":-0.03118896484375,"y":0.286407470703125},{"x":0.02362060546875,"y":0.0706787109375},{"x":0.226806640625,"y":0.013336181640625},{"x":0.088958740234375,"y":-0.07550048828125},{"x":0.28619384765625,"y":-0.1903076171875},{"x":0.05059814453125,"y":0.005950927734375}],"optimisedCameraToObject":{"translation":{"x":-0.09518515538376186,"y":0.126925774049029,"z":0.5482633068597113},"rotation":{"quaternion":{"W":0.6871067184728075,"X":-0.27190956974298647,"Y":0.11861693548363465,"Z":-0.6632341712609396}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":122.4951171875,"y":458.1448669433594},{"x":126.37175750732422,"y":421.370361328125},{"x":130.33465576171875,"y":385.3718566894531},{"x":134.01129150390625,"y":349.9536437988281},{"x":137.651123046875,"y":315.29107666015625},{"x":141.28518676757812,"y":281.1043395996094},{"x":144.8386688232422,"y":247.3619384765625},{"x":152.32261657714844,"y":459.8633728027344},{"x":156.2317657470703,"y":422.4654846191406},{"x":159.84326171875,"y":385.9749755859375},{"x":163.73048400878906,"y":349.57794189453125},{"x":167.03590393066406,"y":314.4698181152344},{"x":170.4614715576172,"y":279.6520690917969},{"x":173.5269317626953,"y":245.88706970214844},{"x":183.46261596679688,"y":461.9196472167969},{"x":186.97073364257812,"y":423.59954833984375},{"x":190.24990844726562,"y":386.2342834472656},{"x":193.3030242919922,"y":349.79864501953125},{"x":196.49761962890625,"y":313.375732421875},{"x":199.92782592773438,"y":278.447021484375},{"x":203.0685577392578,"y":243.34970092773438},{"x":222.07672119140625,"y":386.7791748046875},{"x":225.52810668945312,"y":349.3181457519531},{"x":228.0299530029297,"y":312.9803161621094},{"x":231.3209991455078,"y":276.629638671875},{"x":233.91973876953125,"y":241.42286682128906},{"x":254.96060180664062,"y":387.3140563964844},{"x":257.66998291015625,"y":349.2704772949219},{"x":260.56646728515625,"y":311.7895812988281},{"x":263.04107666015625,"y":275.2820129394531},{"x":265.9085388183594,"y":239.3726806640625},{"x":283.4418029785156,"y":467.6966857910156},{"x":286.5360412597656,"y":427.32330322265625},{"x":288.8804626464844,"y":387.8758544921875},{"x":291.48907470703125,"y":348.689453125},{"x":294.0779724121094,"y":310.9056701660156},{"x":296.4833984375,"y":273.5016784667969},{"x":299.2183837890625,"y":236.6255645751953},{"x":319.64459228515625,"y":469.91107177734375},{"x":326.6069030761719,"y":348.4687805175781},{"x":328.87640380859375,"y":309.8497619628906},{"x":330.9272155761719,"y":271.7351379394531},{"x":333.1919250488281,"y":234.39529418945312}],"reprojectionErrors":[{"x":0.2698516845703125,"y":-0.23883056640625},{"x":0.2791290283203125,"y":-0.05194091796875},{"x":0.1256103515625,"y":0.00677490234375},{"x":0.1840057373046875,"y":0.1143798828125},{"x":0.20697021484375,"y":0.077606201171875},{"x":0.16546630859375,"y":0.15899658203125},{"x":0.136260986328125,"y":0.37335205078125},{"x":0.220123291015625,"y":-0.134002685546875},{"x":-0.0019989013671875,"y":-0.023101806640625},{"x":-3.662109375E-4,"y":-0.147064208984375},{"x":-0.3462371826171875,"y":0.288238525390625},{"x":-0.17999267578125,"y":0.068511962890625},{"x":-0.2016143798828125,"y":0.174041748046875},{"x":0.0710601806640625,"y":-0.175048828125},{"x":-0.0106353759765625,"y":-0.29681396484375},{"x":-0.048583984375,"y":0.0087890625},{"x":0.071563720703125,"y":0.05810546875},{"x":0.349029541015625,"y":-0.144439697265625},{"x":0.41827392578125,"y":0.298065185546875},{"x":0.187103271484375,"y":-0.115081787109375},{"x":0.182464599609375,"y":0.26043701171875},{"x":-0.11517333984375,"y":-0.006134033203125},{"x":-0.4654693603515625,"y":0.113372802734375},{"x":0.070465087890625,"y":-0.207244873046875},{"x":-0.244232177734375,"y":0.1478271484375},{"x":0.07373046875,"y":0.00225830078125},{"x":-0.126617431640625,"y":-0.043243408203125},{"x":0.015106201171875,"y":-0.073028564453125},{"x":-0.089599609375,"y":0.044464111328125},{"x":0.170013427734375,"y":-0.122894287109375},{"x":-0.019073486328125,"y":-0.2205963134765625},{"x":0.245025634765625,"y":0.072052001953125},{"x":-0.155731201171875,"y":0.06103515625},{"x":0.135040283203125,"y":-0.089111328125},{"x":0.105072021484375,"y":0.261871337890625},{"x":0.04010009765625,"y":-0.05133056640625},{"x":0.10546875,"y":-0.028594970703125},{"x":-0.210174560546875,"y":0.1602020263671875},{"x":0.22662353515625,"y":0.078216552734375},{"x":0.26397705078125,"y":0.223602294921875},{"x":0.22650146484375,"y":-0.018310546875},{"x":0.359771728515625,"y":-0.01995849609375},{"x":0.232635498046875,"y":-0.0748443603515625}],"optimisedCameraToObject":{"translation":{"x":-0.2046905252678318,"y":0.11892172544637528,"z":0.4853257408345062},"rotation":{"quaternion":{"W":0.6974904457946051,"X":-0.18841801640828526,"Y":0.06388013182152003,"Z":-0.6884221509193872}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":445.3091735839844,"y":493.79058837890625},{"x":437.9493408203125,"y":450.8716735839844},{"x":430.95269775390625,"y":410.344970703125},{"x":424.37554931640625,"y":371.46588134765625},{"x":418.1058044433594,"y":334.8980407714844},{"x":411.9972229003906,"y":299.5243835449219},{"x":406.2022705078125,"y":266.0498046875},{"x":479.180419921875,"y":483.7961120605469},{"x":470.79278564453125,"y":439.3201904296875},{"x":462.5880126953125,"y":397.4703369140625},{"x":454.72509765625,"y":357.5310974121094},{"x":447.69091796875,"y":319.8810729980469},{"x":440.5931091308594,"y":283.8363037109375},{"x":434.1422424316406,"y":249.26980590820312},{"x":515.9674682617188,"y":472.81890869140625},{"x":505.9195251464844,"y":426.8695983886719},{"x":496.4421691894531,"y":383.8868408203125},{"x":487.645751953125,"y":342.5760498046875},{"x":479.2471008300781,"y":303.65679931640625},{"x":471.2571716308594,"y":266.4480895996094},{"x":463.8814392089844,"y":231.15550231933594},{"x":555.9556274414062,"y":460.8598937988281},{"x":544.043212890625,"y":413.33563232421875},{"x":533.5546875,"y":368.697265625},{"x":523.1531982421875,"y":326.2845458984375},{"x":513.7904663085938,"y":286.06866455078125},{"x":504.3975524902344,"y":247.9456329345703},{"x":495.9871826171875,"y":211.6075439453125},{"x":599.5257568359375,"y":448.10247802734375},{"x":586.2268676757812,"y":398.37030029296875},{"x":574.0136108398438,"y":352.1867980957031},{"x":562.0319213867188,"y":308.29876708984375},{"x":550.7474365234375,"y":267.3061218261719},{"x":540.4179077148438,"y":227.881591796875},{"x":530.447021484375,"y":190.51866149902344},{"x":648.13134765625,"y":433.6322937011719},{"x":632.4238891601562,"y":382.1872863769531},{"x":618.2030639648438,"y":334.1099853515625},{"x":604.5850219726562,"y":288.97943115234375},{"x":591.6318969726562,"y":246.4053955078125},{"x":579.705078125,"y":205.65313720703125},{"x":568.2752685546875,"y":167.4757843017578},{"x":701.150634765625,"y":417.9091796875},{"x":683.0245361328125,"y":364.32745361328125},{"x":666.5355834960938,"y":314.7562255859375},{"x":650.7706298828125,"y":267.53582763671875},{"x":636.022705078125,"y":223.75694274902344},{"x":622.009033203125,"y":182.03199768066406},{"x":609.1029052734375,"y":142.7529296875}],"reprojectionErrors":[{"x":0.04302978515625,"y":0.168365478515625},{"x":0.087249755859375,"y":0.35406494140625},{"x":0.113861083984375,"y":0.21551513671875},{"x":0.0418701171875,"y":0.349212646484375},{"x":-0.03912353515625,"y":-0.042816162109375},{"x":-0.003265380859375,"y":0.03448486328125},{"x":-0.0216064453125,"y":-0.234954833984375},{"x":0.019927978515625,"y":0.048309326171875},{"x":-0.0745849609375,"y":0.34039306640625},{"x":0.066253662109375,"y":0.2279052734375},{"x":0.252349853515625,"y":0.261260986328125},{"x":-0.03118896484375,"y":-0.08734130859375},{"x":0.082489013671875,"y":-0.268951416015625},{"x":-0.14019775390625,"y":-0.2791900634765625},{"x":-0.030029296875,"y":0.042510986328125},{"x":0.1939697265625,"y":0.25860595703125},{"x":0.353363037109375,"y":-0.099090576171875},{"x":0.298675537109375,"y":0.0792236328125},{"x":0.277923583984375,"y":-0.09228515625},{"x":0.24847412109375,"y":-0.082550048828125},{"x":-0.02386474609375,"y":-0.2327728271484375},{"x":-9.765625E-4,"y":0.032440185546875},{"x":0.5364990234375,"y":0.165618896484375},{"x":0.2626953125,"y":-0.0025634765625},{"x":0.4652099609375,"y":-0.0196533203125},{"x":0.148193359375,"y":-0.042938232421875},{"x":0.3409423828125,"y":-0.135498046875},{"x":-0.0048828125,"y":-0.140045166015625},{"x":0.19134521484375,"y":-0.305145263671875},{"x":0.312744140625,"y":0.258819580078125},{"x":0.091552734375,"y":0.07415771484375},{"x":0.31964111328125,"y":0.159393310546875},{"x":0.47576904296875,"y":-0.2945556640625},{"x":0.25262451171875,"y":-0.1474151611328125},{"x":0.20196533203125,"y":-0.060455322265625},{"x":-0.34912109375,"y":-0.223419189453125},{"x":0.0733642578125,"y":0.144805908203125},{"x":-0.0869140625,"y":0.188812255859375},{"x":-0.02508544921875,"y":0.0631103515625},{"x":0.12640380859375,"y":-0.078338623046875},{"x":-0.05621337890625,"y":0.289031982421875},{"x":-0.099365234375,"y":0.2244873046875},{"x":-0.3267822265625,"y":-0.384796142578125},{"x":0.0340576171875,"y":0.066741943359375},{"x":-0.13836669921875,"y":-0.172454833984375},{"x":-0.0321044921875,"y":0.25299072265625},{"x":-0.0294189453125,"y":-0.0157623291015625},{"x":0.07366943359375,"y":0.17156982421875},{"x":-0.166259765625,"y":0.212310791015625}],"optimisedCameraToObject":{"translation":{"x":0.024343255829322494,"y":0.13137020501020133,"z":0.40580251800220485},"rotation":{"quaternion":{"W":0.538801199747668,"X":-0.37765832161691343,"Y":0.14615294411114807,"Z":-0.7387196871558337}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":426.6737365722656,"y":389.1740417480469},{"x":418.7730712890625,"y":347.9432067871094},{"x":410.9595642089844,"y":308.4597473144531},{"x":403.6623840332031,"y":270.0485534667969},{"x":396.4604797363281,"y":233.11183166503906},{"x":389.4702453613281,"y":197.28878784179688},{"x":382.929443359375,"y":162.63804626464844},{"x":459.5875244140625,"y":377.33099365234375},{"x":450.6039733886719,"y":334.5773620605469},{"x":442.0779113769531,"y":293.6548156738281},{"x":433.91064453125,"y":253.93704223632812},{"x":425.93841552734375,"y":215.9028778076172},{"x":418.10589599609375,"y":178.82383728027344},{"x":410.8338623046875,"y":143.1826629638672},{"x":495.0691833496094,"y":364.545654296875},{"x":485.27008056640625,"y":319.994873046875},{"x":475.875,"y":277.53179931640625},{"x":466.5834655761719,"y":236.47218322753906},{"x":457.7644958496094,"y":196.99398803710938},{"x":449.0135192871094,"y":158.85430908203125},{"x":440.7919616699219,"y":122.23661041259766},{"x":534.7682495117188,"y":350.08697509765625},{"x":523.3123168945312,"y":304.2135009765625},{"x":512.598876953125,"y":259.9389953613281},{"x":502.0291748046875,"y":217.46812438964844},{"x":492.3134460449219,"y":176.5423126220703},{"x":482.801513671875,"y":137.0210723876953},{"x":473.4211730957031,"y":99.06161499023438},{"x":577.5963745117188,"y":334.8580627441406},{"x":565.0200805664062,"y":286.4747619628906},{"x":552.9630737304688,"y":240.78065490722656},{"x":541.1199340820312,"y":196.5331573486328},{"x":529.9544067382812,"y":154.2593536376953},{"x":519.1378784179688,"y":113.32495880126953},{"x":508.89337158203125,"y":74.07524871826172},{"x":625.8919677734375,"y":317.292724609375},{"x":611.186279296875,"y":267.0841369628906},{"x":597.3160400390625,"y":219.38978576660156},{"x":584.113037109375,"y":173.51905822753906},{"x":571.593505859375,"y":129.3987579345703},{"x":559.3279418945312,"y":87.29229736328125},{"x":678.9515991210938,"y":298.3379211425781},{"x":662.1456298828125,"y":245.81866455078125},{"x":646.5789184570312,"y":195.8288116455078},{"x":631.2039184570312,"y":148.28628540039062},{"x":616.9508666992188,"y":102.4796371459961}],"reprojectionErrors":[{"x":-0.071624755859375,"y":0.434844970703125},{"x":-0.0765380859375,"y":0.35101318359375},{"x":0.107940673828125,"y":0.010101318359375},{"x":0.03759765625,"y":0.0064697265625},{"x":0.11962890625,"y":-0.1371917724609375},{"x":0.224578857421875,"y":-0.1298675537109375},{"x":0.102691650390625,"y":-0.0952301025390625},{"x":0.002044677734375,"y":0.333221435546875},{"x":0.11358642578125,"y":0.2540283203125},{"x":0.0924072265625,"y":-0.0472412109375},{"x":0.0189208984375,"y":-0.034942626953125},{"x":0.039886474609375,"y":-0.2719573974609375},{"x":0.194915771484375,"y":-0.1076812744140625},{"x":0.048583984375,"y":-0.0972900390625},{"x":0.46624755859375,"y":0.0963134765625},{"x":0.282135009765625,"y":0.182525634765625},{"x":0.076934814453125,"y":-0.076446533203125},{"x":0.12860107421875,"y":-0.09869384765625},{"x":0.04742431640625,"y":-0.1566314697265625},{"x":0.21868896484375,"y":-0.0947113037109375},{"x":0.163238525390625,"y":-0.1772918701171875},{"x":0.09320068359375,"y":0.301513671875},{"x":0.28094482421875,"y":-0.0474853515625},{"x":0.1796875,"y":-0.102203369140625},{"x":0.3604736328125,"y":-0.1832733154296875},{"x":0.08746337890625,"y":-0.138885498046875},{"x":-0.012786865234375,"y":0.0731048583984375},{"x":0.1102294921875,"y":0.20470428466796875},{"x":0.47705078125,"y":-0.13848876953125},{"x":0.28997802734375,"y":0.123779296875},{"x":0.12347412109375,"y":-0.2387847900390625},{"x":0.24847412109375,"y":-0.1157989501953125},{"x":0.16949462890625,"y":-0.155609130859375},{"x":0.18603515625,"y":0.164825439453125},{"x":0.048248291015625,"y":0.3978424072265625},{"x":-0.1083984375,"y":0.11956787109375},{"x":0.08197021484375,"y":0.151336669921875},{"x":0.08355712890625,"y":-0.0714263916015625},{"x":0.0211181640625,"y":-0.009796142578125},{"x":-0.1612548828125,"y":0.2709197998046875},{"x":-0.0703125,"y":0.38077545166015625},{"x":-0.21209716796875,"y":-0.143707275390625},{"x":0.0103759765625,"y":-0.033111572265625},{"x":-0.226806640625,"y":0.0319976806640625},{"x":0.06890869140625,"y":-0.0414886474609375},{"x":-0.08270263671875,"y":0.298736572265625}],"optimisedCameraToObject":{"translation":{"x":0.01438411114847998,"y":0.07028207887682282,"z":0.4106359615008526},"rotation":{"quaternion":{"W":0.5488372732207907,"X":-0.34057439994580646,"Y":0.18951904724649454,"Z":-0.7395060894650577}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":336.0992736816406,"y":450.7295837402344},{"x":330.17083740234375,"y":407.78277587890625},{"x":324.2337341308594,"y":366.17236328125},{"x":318.62591552734375,"y":325.1539306640625},{"x":312.99359130859375,"y":284.66168212890625},{"x":307.50823974609375,"y":244.9515380859375},{"x":302.14520263671875,"y":205.8055419921875},{"x":372.19232177734375,"y":446.0866394042969},{"x":365.6128234863281,"y":401.2141418457031},{"x":359.5612487792969,"y":358.6602783203125},{"x":353.19561767578125,"y":316.1836853027344},{"x":347.29345703125,"y":274.81805419921875},{"x":341.0802917480469,"y":233.82858276367188},{"x":335.20855712890625,"y":193.70814514160156},{"x":410.4276428222656,"y":440.6930236816406},{"x":403.4933166503906,"y":395.10687255859375},{"x":396.7280578613281,"y":350.6271667480469},{"x":389.8565368652344,"y":307.0006103515625},{"x":382.9920959472656,"y":264.4310607910156},{"x":376.50872802734375,"y":222.20004272460938},{"x":370.0980224609375,"y":180.96224975585938},{"x":451.6286926269531,"y":434.99969482421875},{"x":443.31341552734375,"y":387.7292785644531},{"x":436.4273681640625,"y":342.23748779296875},{"x":428.53594970703125,"y":297.1686096191406},{"x":421.8755798339844,"y":252.98545837402344},{"x":414.9505310058594,"y":209.75112915039062},{"x":407.7071228027344,"y":167.4571075439453},{"x":495.0468444824219,"y":428.8992004394531},{"x":487.02984619140625,"y":380.0477294921875},{"x":478.757568359375,"y":333.0668029785156},{"x":470.59307861328125,"y":286.4486389160156},{"x":462.71307373046875,"y":241.2969512939453},{"x":455.0159606933594,"y":196.55776977539062},{"x":447.17840576171875,"y":152.81019592285156},{"x":542.7650146484375,"y":422.8598327636719},{"x":533.2032470703125,"y":372.302978515625},{"x":524.145751953125,"y":323.4279479980469},{"x":515.4201049804688,"y":275.1698303222656},{"x":506.90252685546875,"y":228.2960205078125},{"x":498.3807067871094,"y":182.18374633789062},{"x":490.1771545410156,"y":137.3330841064453},{"x":592.6115112304688,"y":415.86029052734375},{"x":582.9214477539062,"y":364.2237243652344},{"x":573.040283203125,"y":313.0414123535156},{"x":563.4664306640625,"y":263.2950134277344},{"x":553.6317749023438,"y":214.78819274902344},{"x":544.8323364257812,"y":166.8851318359375},{"x":535.7742309570312,"y":120.09036254882812}],"reprojectionErrors":[{"x":0.082855224609375,"y":0.018890380859375},{"x":0.11480712890625,"y":0.279510498046875},{"x":0.253875732421875,"y":-0.027740478515625},{"x":0.15924072265625,"y":-0.1810302734375},{"x":0.181884765625,"y":-0.13629150390625},{"x":0.147613525390625,"y":-0.170318603515625},{"x":0.0784912109375,"y":-0.08526611328125},{"x":-0.005828857421875,"y":-0.264251708984375},{"x":0.1539306640625,"y":0.622589111328125},{"x":-0.10235595703125,"y":0.007293701171875},{"x":0.0638427734375,"y":0.106597900390625},{"x":-0.128204345703125,"y":-0.136932373046875},{"x":0.09283447265625,"y":-0.011199951171875},{"x":0.07147216796875,"y":-0.0309906005859375},{"x":0.119110107421875,"y":-0.118377685546875},{"x":0.053436279296875,"y":0.099853515625},{"x":-0.054107666015625,"y":0.080841064453125},{"x":0.06793212890625,"y":0.050872802734375},{"x":0.30230712890625,"y":-0.219818115234375},{"x":0.271453857421875,"y":-0.03765869140625},{"x":0.280181884765625,"y":-0.081207275390625},{"x":-0.121917724609375,"y":-0.027740478515625},{"x":0.547760009765625,"y":0.401580810546875},{"x":-0.06683349609375,"y":-0.0205078125},{"x":0.464324951171875,"y":0.032073974609375},{"x":-0.0997314453125,"y":0.0680084228515625},{"x":-0.26751708984375,"y":-0.0030517578125},{"x":0.01055908203125,"y":-0.1987152099609375},{"x":0.29840087890625,"y":0.077056884765625},{"x":-0.0509033203125,"y":0.51409912109375},{"x":0.020660400390625,"y":0.0718994140625},{"x":0.144500732421875,"y":0.2255859375},{"x":0.138702392578125,"y":-0.1599578857421875},{"x":0.099822998046875,"y":-0.0606842041015625},{"x":0.34637451171875,"y":-0.08441162109375},{"x":-0.3829345703125,"y":-0.315948486328125},{"x":0.005126953125,"y":0.14239501953125},{"x":0.07843017578125,"y":-0.0186767578125},{"x":0.0029296875,"y":0.2294921875},{"x":-0.103790283203125,"y":0.0849456787109375},{"x":-0.03533935546875,"y":0.1373748779296875},{"x":-0.119873046875,"y":-0.1449432373046875},{"x":0.375,"y":-0.23583984375},{"x":-0.01678466796875,"y":-0.50469970703125},{"x":1.220703125E-4,"y":-0.0863037109375},{"x":-0.0804443359375,"y":-0.002593994140625},{"x":0.30230712890625,"y":-0.0955963134765625},{"x":-0.15460205078125,"y":0.23388671875},{"x":-0.16400146484375,"y":0.44632720947265625}],"optimisedCameraToObject":{"translation":{"x":-0.0433889237584961,"y":0.1048406924754852,"z":0.4157938970622981},"rotation":{"quaternion":{"W":0.6135297158716464,"X":-0.22215609221931834,"Y":0.14971658534003923,"Z":-0.7428411017885436}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img11.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":260.2383728027344,"y":374.4985656738281},{"x":253.2475128173828,"y":334.1517333984375},{"x":245.428955078125,"y":293.0289306640625},{"x":238.48843383789062,"y":251.04409790039062},{"x":230.51426696777344,"y":208.37680053710938},{"x":222.7057342529297,"y":164.11351013183594},{"x":214.5968475341797,"y":119.59557342529297},{"x":297.66693115234375,"y":372.0448913574219},{"x":290.93023681640625,"y":330.68206787109375},{"x":283.7845153808594,"y":288.8488464355469},{"x":276.1915588378906,"y":245.90829467773438},{"x":268.988525390625,"y":202.26046752929688},{"x":261.06671142578125,"y":157.1305389404297},{"x":253.72142028808594,"y":111.63555145263672},{"x":336.2612609863281,"y":369.3024597167969},{"x":329.7908020019531,"y":327.08807373046875},{"x":322.9806823730469,"y":284.2085876464844},{"x":315.9197998046875,"y":240.21987915039062},{"x":308.8097839355469,"y":195.78887939453125},{"x":301.183349609375,"y":149.9733428955078},{"x":293.8123474121094,"y":102.9659423828125},{"x":376.9502258300781,"y":366.37030029296875},{"x":370.40118408203125,"y":323.36773681640625},{"x":363.93505859375,"y":279.6013488769531},{"x":357.23858642578125,"y":234.8330535888672},{"x":350.2254333496094,"y":188.84457397460938},{"x":343.1197204589844,"y":141.85488891601562},{"x":335.94439697265625,"y":93.91809844970703},{"x":418.87567138671875,"y":363.4874267578125},{"x":412.85992431640625,"y":319.4976806640625},{"x":406.3627014160156,"y":274.69854736328125},{"x":400.0781555175781,"y":228.94903564453125},{"x":393.5906066894531,"y":181.91111755371094},{"x":386.78131103515625,"y":133.4115753173828},{"x":379.8738098144531,"y":84.46639251708984},{"x":463.07220458984375,"y":360.3866882324219},{"x":457.05767822265625,"y":315.3857421875},{"x":451.14630126953125,"y":269.92071533203125},{"x":445.4580383300781,"y":222.62460327148438},{"x":439.0089111328125,"y":174.61700439453125},{"x":432.9885559082031,"y":125.10078430175781},{"x":426.19305419921875,"y":75.09606170654297},{"x":508.95697021484375,"y":357.3693542480469},{"x":503.73138427734375,"y":311.2913818359375},{"x":497.6918029785156,"y":263.94677734375},{"x":492.3437194824219,"y":215.91818237304688},{"x":486.3887939453125,"y":166.45938110351562},{"x":480.7103576660156,"y":115.74801635742188},{"x":474.6815490722656,"y":63.966156005859375}],"reprojectionErrors":[{"x":0.2235107421875,"y":-0.15057373046875},{"x":0.00927734375,"y":-0.129913330078125},{"x":0.4741668701171875,"y":-0.126312255859375},{"x":-0.0923919677734375,"y":-0.07965087890625},{"x":0.2162017822265625,"y":-0.196624755859375},{"x":0.195404052734375,"y":0.4080352783203125},{"x":0.3056793212890625,"y":0.36339569091796875},{"x":0.018341064453125,"y":-0.23974609375},{"x":-0.228179931640625,"y":-0.062591552734375},{"x":-0.21221923828125,"y":-0.24200439453125},{"x":0.09954833984375,"y":-0.1686553955078125},{"x":-0.13507080078125,"y":-0.2714385986328125},{"x":0.187286376953125,"y":0.194366455078125},{"x":-0.2342529296875,"y":0.08020782470703125},{"x":0.196044921875,"y":-0.140869140625},{"x":-0.0699462890625,"y":-0.010223388671875},{"x":-0.14013671875,"y":-0.077667236328125},{"x":-0.1082763671875,"y":0.071533203125},{"x":-0.18115234375,"y":-0.26025390625},{"x":0.103240966796875,"y":-0.1628875732421875},{"x":-0.032562255859375,"y":0.13730621337890625},{"x":-0.069427490234375,"y":0.040283203125},{"x":0.017578125,"y":0.019805908203125},{"x":-0.1187744140625,"y":-0.13873291015625},{"x":-0.17010498046875,"y":-0.2285614013671875},{"x":-0.055145263671875,"y":-0.064208984375},{"x":-0.00335693359375,"y":0.1010894775390625},{"x":-0.043304443359375,"y":0.17725372314453125},{"x":0.192230224609375,"y":0.057464599609375},{"x":0.051055908203125,"y":0.040740966796875},{"x":0.255157470703125,"y":-0.109893798828125},{"x":0.105560302734375,"y":-0.286895751953125},{"x":0.01287841796875,"y":-0.1872406005859375},{"x":0.090576171875,"y":0.3255767822265625},{"x":0.109588623046875,"y":0.19708251953125},{"x":0.068939208984375,"y":0.1697998046875},{"x":0.265777587890625,"y":0.133514404296875},{"x":0.228515625,"y":-0.42633056640625},{"x":-0.1676025390625,"y":-0.1785430908203125},{"x":0.05645751953125,"y":-0.28021240234375},{"x":-0.294158935546875,"y":0.02648162841796875},{"x":-0.020965576171875,"y":-0.3198699951171875},{"x":0.277618408203125,"y":0.0672607421875},{"x":0.06280517578125,"y":0.0264892578125},{"x":0.537384033203125,"y":0.217041015625},{"x":0.19122314453125,"y":0.0179290771484375},{"x":0.31781005859375,"y":0.1351776123046875},{"x":0.02880859375,"y":0.34893798828125},{"x":-0.0543212890625,"y":0.43274688720703125}],"optimisedCameraToObject":{"translation":{"x":-0.09323704737422726,"y":0.05758486917742928,"z":0.4339210602781248},"rotation":{"quaternion":{"W":0.65187017335474,"X":-0.0515536759909429,"Y":0.1815601244380711,"Z":-0.7344681182980746}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img12.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":175.2587127685547,"y":262.1934509277344},{"x":165.4022979736328,"y":221.11801147460938},{"x":154.51283264160156,"y":177.74122619628906},{"x":143.04641723632812,"y":130.99993896484375},{"x":130.8199462890625,"y":81.38884735107422},{"x":217.1041717529297,"y":260.9322204589844},{"x":208.28817749023438,"y":219.34365844726562},{"x":198.73565673828125,"y":175.5475311279297},{"x":188.38568115234375,"y":128.42105102539062},{"x":177.70162963867188,"y":78.15001678466797},{"x":259.1092834472656,"y":259.4769592285156},{"x":251.3468475341797,"y":217.60580444335938},{"x":242.93272399902344,"y":173.066650390625},{"x":234.338623046875,"y":125.68207550048828},{"x":224.82501220703125,"y":74.68567657470703},{"x":301.793701171875,"y":258.0327453613281},{"x":295.46368408203125,"y":215.79266357421875},{"x":288.7605285644531,"y":170.98489379882812},{"x":281.4442443847656,"y":122.79698944091797},{"x":273.71966552734375,"y":71.47286224365234},{"x":345.0747985839844,"y":256.4622802734375},{"x":340.12567138671875,"y":213.88926696777344},{"x":334.7135314941406,"y":168.38221740722656},{"x":328.88275146484375,"y":120.16633605957031},{"x":322.9318542480469,"y":67.87232208251953},{"x":389.13836669921875,"y":255.2708282470703},{"x":385.76617431640625,"y":211.94696044921875},{"x":381.6854553222656,"y":166.3241729736328},{"x":377.5753479003906,"y":116.93194580078125},{"x":373.24298095703125,"y":64.08035278320312},{"x":433.96490478515625,"y":253.35287475585938},{"x":432.0233459472656,"y":209.797607421875},{"x":429.23406982421875,"y":163.31716918945312},{"x":427.06524658203125,"y":114.01258850097656},{"x":424.24920654296875,"y":60.145748138427734}],"reprojectionErrors":[{"x":0.2497711181640625,"y":-0.212127685546875},{"x":0.0957183837890625,"y":-0.0219268798828125},{"x":0.335693359375,"y":-0.11260986328125},{"x":0.4503173828125,"y":0.3233642578125},{"x":0.550811767578125,"y":0.5007171630859375},{"x":-0.372161865234375,"y":-0.32635498046875},{"x":-0.383819580078125,"y":-0.044921875},{"x":-0.227752685546875,"y":-0.189849853515625},{"x":0.10009765625,"y":0.0983428955078125},{"x":0.0716552734375,"y":0.3342132568359375},{"x":-0.410980224609375,"y":-0.262786865234375},{"x":-0.248260498046875,"y":-0.1302337646484375},{"x":0.07183837890625,"y":-0.0170135498046875},{"x":0.0276947021484375,"y":-0.01702880859375},{"x":0.302001953125,"y":0.32698822021484375},{"x":-0.36236572265625,"y":-0.227020263671875},{"x":-0.3568115234375,"y":-0.1669464111328125},{"x":-0.3934326171875,"y":-0.281707763671875},{"x":-0.2745361328125,"y":-0.0385284423828125},{"x":-0.253265380859375,"y":-3.8909912109375E-4},{"x":-0.11859130859375,"y":-0.08233642578125},{"x":-0.169158935546875,"y":-0.141021728515625},{"x":-0.088134765625,"y":-0.06524658203125},{"x":0.045989990234375,"y":-0.36858367919921875},{"x":-0.104339599609375,"y":-0.0112152099609375},{"x":0.16064453125,"y":-0.334625244140625},{"x":-0.09014892578125,"y":-0.10479736328125},{"x":0.125213623046875,"y":-0.4345855712890625},{"x":0.10235595703125,"y":-0.1510009765625},{"x":0.0052490234375,"y":0.09557342529296875},{"x":0.5220947265625,"y":0.1209716796875},{"x":0.27191162109375,"y":0.108856201171875},{"x":0.721588134765625,"y":0.10235595703125},{"x":0.3873291015625,"y":-0.3065948486328125},{"x":0.51904296875,"y":0.2683868408203125}],"optimisedCameraToObject":{"translation":{"x":-0.14314394006926248,"y":-0.014016448200971678,"z":0.42005918231579104},"rotation":{"quaternion":{"W":0.6644392231905237,"X":0.12735906096681107,"Y":0.22229371472010778,"Z":-0.702058183252329}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img13.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":149.26956176757812,"y":449.7602233886719},{"x":139.1857452392578,"y":411.1377868652344},{"x":129.00082397460938,"y":370.991455078125},{"x":117.84774780273438,"y":328.88677978515625},{"x":106.24641418457031,"y":285.12890625},{"x":94.14816284179688,"y":239.1292266845703},{"x":81.21599578857422,"y":190.89248657226562},{"x":191.87452697753906,"y":444.94757080078125},{"x":183.02308654785156,"y":406.425048828125},{"x":173.39144897460938,"y":366.00201416015625},{"x":163.04624938964844,"y":323.8812561035156},{"x":152.85081481933594,"y":279.97857666015625},{"x":141.8389892578125,"y":233.65328979492188},{"x":130.13523864746094,"y":185.29273986816406},{"x":234.4678955078125,"y":440.66375732421875},{"x":226.27761840820312,"y":401.47491455078125},{"x":217.71595764160156,"y":361.4081115722656},{"x":208.78196716308594,"y":318.9676208496094},{"x":199.51051330566406,"y":274.82171630859375},{"x":189.19371032714844,"y":227.9902801513672},{"x":178.58627319335938,"y":179.6941680908203},{"x":277.36798095703125,"y":435.9306335449219},{"x":269.88507080078125,"y":396.9957580566406},{"x":262.4490661621094,"y":356.2088928222656},{"x":254.3917694091797,"y":314.03765869140625},{"x":246.1138458251953,"y":269.7975769042969},{"x":236.87899780273438,"y":222.95538330078125},{"x":227.86679077148438,"y":174.02284240722656},{"x":320.12884521484375,"y":431.6480407714844},{"x":313.65057373046875,"y":392.3100891113281},{"x":306.99017333984375,"y":351.7143249511719},{"x":299.9317626953125,"y":309.07318115234375},{"x":292.8251037597656,"y":264.3307189941406},{"x":284.8241882324219,"y":217.70352172851562},{"x":276.43621826171875,"y":168.1683349609375},{"x":363.37896728515625,"y":426.9630432128906},{"x":357.74932861328125,"y":387.8048095703125},{"x":351.9930114746094,"y":346.9402160644531},{"x":345.53594970703125,"y":303.8026428222656},{"x":339.8978271484375,"y":259.01318359375},{"x":333.09918212890625,"y":211.8115692138672},{"x":325.9619140625,"y":163.01002502441406},{"x":406.0725402832031,"y":422.57867431640625},{"x":401.7575988769531,"y":383.22784423828125},{"x":396.8459167480469,"y":341.8607482910156},{"x":392.0191345214844,"y":298.8531494140625},{"x":386.7174377441406,"y":253.75343322753906},{"x":381.09124755859375,"y":206.37832641601562},{"x":375.672607421875,"y":156.86903381347656}],"reprojectionErrors":[{"x":0.2923736572265625,"y":-0.574676513671875},{"x":0.330902099609375,"y":-0.253387451171875},{"x":0.017425537109375,"y":-0.11187744140625},{"x":0.18732452392578125,"y":0.1651611328125},{"x":0.28600311279296875,"y":0.142059326171875},{"x":0.32403564453125,"y":0.2642059326171875},{"x":0.5965194702148438,"y":0.369232177734375},{"x":0.0076904296875,"y":-0.187225341796875},{"x":-0.2828521728515625,"y":-0.14862060546875},{"x":-0.2060699462890625,"y":0.07464599609375},{"x":0.1424407958984375,"y":0.159515380859375},{"x":-0.1323089599609375,"y":0.058380126953125},{"x":-0.0989837646484375,"y":0.2673187255859375},{"x":0.0796661376953125,"y":0.2397613525390625},{"x":-0.08331298828125,"y":-0.33721923828125},{"x":-0.1239013671875,"y":0.1827392578125},{"x":-0.1652374267578125,"y":-0.147552490234375},{"x":-0.2324981689453125,"y":0.046142578125},{"x":-0.3892364501953125,"y":-0.037445068359375},{"x":0.041015625,"y":0.4356689453125},{"x":0.2689208984375,"y":0.0837860107421875},{"x":-0.2939453125,"y":-0.046966552734375},{"x":-0.122711181640625,"y":0.0318603515625},{"x":-0.329254150390625,"y":0.221832275390625},{"x":-0.2686004638671875,"y":-0.0672607421875},{"x":-0.36700439453125,"y":-0.285308837890625},{"x":0.0838165283203125,"y":-0.046661376953125},{"x":-0.1265869140625,"y":-0.0255584716796875},{"x":-0.17315673828125,"y":-0.216766357421875},{"x":-0.0791015625,"y":0.075714111328125},{"x":-0.091888427734375,"y":-0.127685546875},{"x":-0.01605224609375,"y":-0.16314697265625},{"x":-0.22369384765625,"y":-0.1104736328125},{"x":0.10662841796875,"y":-0.335296630859375},{"x":0.440643310546875,"y":0.0213775634765625},{"x":-0.34429931640625,"y":0.005859375},{"x":-0.162841796875,"y":-0.0731201171875},{"x":-0.101226806640625,"y":-0.212493896484375},{"x":0.39715576171875,"y":0.029449462890625},{"x":-0.206512451171875,"y":-0.105560302734375},{"x":0.046234130859375,"y":-0.00787353515625},{"x":0.310302734375,"y":-0.6556243896484375},{"x":0.243682861328125,"y":-0.08258056640625},{"x":0.055328369140625,"y":-0.1630859375},{"x":0.26025390625,"y":-0.00732421875},{"x":0.162322998046875,"y":-0.11724853515625},{"x":0.305572509765625,"y":-0.1798095703125},{"x":0.52215576171875,"y":-0.163909912109375},{"x":0.2608642578125,"y":-0.3784942626953125}],"optimisedCameraToObject":{"translation":{"x":-0.15809515499741053,"y":0.10012872337508279,"z":0.4149613197958304},"rotation":{"quaternion":{"W":0.6550149853522361,"X":0.11736778328522585,"Y":0.12899457620510382,"Z":-0.7352146432983961}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img14.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":173.53370666503906,"y":390.35504150390625},{"x":163.48095703125,"y":352.9837951660156},{"x":152.83775329589844,"y":313.1433410644531},{"x":141.3758087158203,"y":270.7834167480469},{"x":129.05450439453125,"y":225.23046875},{"x":115.7383804321289,"y":176.1360626220703},{"x":101.43240356445312,"y":123.71068572998047},{"x":217.342529296875,"y":387.139404296875},{"x":208.72401428222656,"y":349.7161560058594},{"x":199.48411560058594,"y":309.9036560058594},{"x":189.9750518798828,"y":267.28985595703125},{"x":179.01522827148438,"y":221.4867401123047},{"x":167.72259521484375,"y":172.43394470214844},{"x":155.12635803222656,"y":119.43257141113281},{"x":260.5260009765625,"y":384.2875061035156},{"x":253.6577911376953,"y":346.36016845703125},{"x":245.6853485107422,"y":306.7197265625},{"x":237.5360565185547,"y":263.9290466308594},{"x":228.9281005859375,"y":218.1188201904297},{"x":218.928955078125,"y":168.82574462890625},{"x":208.42129516601562,"y":115.28561401367188},{"x":304.5901184082031,"y":381.00274658203125},{"x":298.9429931640625,"y":343.3711242675781},{"x":292.51434326171875,"y":303.3191833496094},{"x":285.865966796875,"y":260.43585205078125},{"x":278.7050476074219,"y":214.3549346923828},{"x":270.59063720703125,"y":164.38783264160156},{"x":262.14410400390625,"y":111.92737579345703},{"x":348.11712646484375,"y":378.2590637207031},{"x":343.64874267578125,"y":340.3801574707031},{"x":339.05914306640625,"y":300.07354736328125},{"x":333.9384765625,"y":256.9925842285156},{"x":328.2062072753906,"y":210.7739715576172},{"x":322.536865234375,"y":160.9962921142578},{"x":315.88714599609375,"y":107.16012573242188},{"x":392.10394287109375,"y":375.087646484375},{"x":389.00469970703125,"y":337.1124572753906},{"x":385.8766174316406,"y":296.85455322265625},{"x":382.12530517578125,"y":253.15086364746094},{"x":378.756103515625,"y":207.01885986328125},{"x":374.6156005859375,"y":156.67498779296875},{"x":370.13031005859375,"y":103.31600189208984},{"x":436.1343994140625,"y":372.3162841796875},{"x":434.36138916015625,"y":334.1383972167969},{"x":432.5819396972656,"y":293.4189147949219},{"x":430.8116760253906,"y":249.90708923339844},{"x":428.6825866699219,"y":203.16021728515625},{"x":426.53753662109375,"y":153.14959716796875},{"x":424.56304931640625,"y":98.65428161621094}],"reprojectionErrors":[{"x":0.2425994873046875,"y":-0.482177734375},{"x":0.2826995849609375,"y":-0.287506103515625},{"x":0.244598388671875,"y":-0.0841064453125},{"x":0.2870941162109375,"y":-0.077484130859375},{"x":0.3712921142578125,"y":0.113311767578125},{"x":0.5413665771484375,"y":0.5006866455078125},{"x":0.686859130859375,"y":0.486053466796875},{"x":-0.2422637939453125,"y":-0.1998291015625},{"x":-0.2618255615234375,"y":-0.12066650390625},{"x":-0.2377166748046875,"y":-0.12890625},{"x":-0.5823516845703125,"y":-0.070526123046875},{"x":-0.1829986572265625,"y":0.1472930908203125},{"x":-0.2366790771484375,"y":0.245758056640625},{"x":0.1359710693359375,"y":0.5319595336914062},{"x":0.0604248046875,"y":-0.27996826171875},{"x":-0.3244171142578125,"y":0.13409423828125},{"x":-0.0907745361328125,"y":-0.231842041015625},{"x":-0.2167510986328125,"y":-0.200958251953125},{"x":-0.478546142578125,"y":-0.2017974853515625},{"x":-0.0103302001953125,"y":-0.113372802734375},{"x":0.2281341552734375,"y":0.43291473388671875},{"x":-0.350738525390625,"y":0.073760986328125},{"x":-0.560882568359375,"y":0.02117919921875},{"x":-0.382171630859375,"y":-0.12091064453125},{"x":-0.417510986328125,"y":-0.20404052734375},{"x":-0.421112060546875,"y":-0.1625823974609375},{"x":-0.006072998046875,"y":0.3464813232421875},{"x":0.143707275390625,"y":-0.46917724609375},{"x":-0.0533447265625,"y":-0.11279296875},{"x":-0.035308837890625,"y":-0.090789794921875},{"x":-0.194549560546875,"y":-0.167877197265625},{"x":-0.152557373046875,"y":-0.26239013671875},{"x":0.13543701171875,"y":-0.314361572265625},{"x":-0.04632568359375,"y":-0.2512664794921875},{"x":0.29779052734375,"y":0.0228729248046875},{"x":-0.03955078125,"y":0.128936767578125},{"x":0.027679443359375,"y":0.072723388671875},{"x":-0.079376220703125,"y":-0.244842529296875},{"x":0.212310791015625,"y":0.071990966796875},{"x":-0.127044677734375,"y":-0.30047607421875},{"x":0.027862548828125,"y":0.069061279296875},{"x":0.21795654296875,"y":-0.42363739013671875},{"x":0.111572265625,"y":-0.02911376953125},{"x":0.282745361328125,"y":-0.0589599609375},{"x":0.353759765625,"y":-0.108795166015625},{"x":0.297821044921875,"y":-0.1976776123046875},{"x":0.470062255859375,"y":-0.1919708251953125},{"x":0.5128173828125,"y":-0.4187164306640625},{"x":0.222442626953125,"y":-0.06854248046875}],"optimisedCameraToObject":{"translation":{"x":-0.14281258697247465,"y":0.06184659107022332,"z":0.41167396044767685},"rotation":{"quaternion":{"W":0.6571156293580589,"X":0.1746380148671069,"Y":0.1832494653850872,"Z":-0.7100142582038181}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img15.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":206.7625274658203,"y":356.50555419921875},{"x":197.00323486328125,"y":321.0496826171875},{"x":186.42527770996094,"y":282.58306884765625},{"x":174.90101623535156,"y":241.12208557128906},{"x":162.3976593017578,"y":196.4661102294922},{"x":148.71311950683594,"y":148.22640991210938},{"x":133.95260620117188,"y":94.54347229003906},{"x":250.083984375,"y":352.8813781738281},{"x":241.8231964111328,"y":316.935791015625},{"x":232.82040405273438,"y":278.90399169921875},{"x":223.3256378173828,"y":236.99050903320312},{"x":212.6238555908203,"y":192.03915405273438},{"x":201.11216735839844,"y":143.16934204101562},{"x":188.6033477783203,"y":90.08890533447266},{"x":292.755615234375,"y":349.2329406738281},{"x":285.9713439941406,"y":313.1385498046875},{"x":278.8077392578125,"y":274.7930603027344},{"x":271.00469970703125,"y":233.00987243652344},{"x":262.48590087890625,"y":187.9469451904297},{"x":252.87559509277344,"y":139.1084442138672},{"x":242.79368591308594,"y":85.13973999023438},{"x":335.74334716796875,"y":345.8541259765625},{"x":330.614501953125,"y":309.6211853027344},{"x":324.87457275390625,"y":270.96990966796875},{"x":318.7822265625,"y":228.9004669189453},{"x":312.255859375,"y":184.15606689453125},{"x":305.9164123535156,"y":134.39471435546875},{"x":297.2127685546875,"y":80.91951751708984},{"x":378.7124938964844,"y":342.14251708984375},{"x":374.77801513671875,"y":306.0675048828125},{"x":370.98095703125,"y":267.03271484375},{"x":366.942626953125,"y":224.87107849121094},{"x":362.08233642578125,"y":179.26953125},{"x":357.2707824707031,"y":130.0432586669922},{"x":351.6556701660156,"y":75.1672134399414},{"x":421.63629150390625,"y":338.2236633300781},{"x":419.4341125488281,"y":301.9865417480469},{"x":417.3532409667969,"y":263.1272277832031},{"x":415.08563232421875,"y":220.64891052246094},{"x":412.5711669921875,"y":175.14051818847656},{"x":409.90338134765625,"y":124.95762634277344},{"x":407.01409912109375,"y":70.54022979736328},{"x":464.4685974121094,"y":334.8310546875},{"x":464.13720703125,"y":298.2650451660156},{"x":463.6222839355469,"y":259.00970458984375},{"x":463.15789794921875,"y":216.7220916748047},{"x":462.38140869140625,"y":170.1407012939453},{"x":462.05157470703125,"y":120.66414642333984},{"x":461.90777587890625,"y":65.6636734008789}],"reprojectionErrors":[{"x":0.203155517578125,"y":-0.23480224609375},{"x":0.1124114990234375,"y":-0.334869384765625},{"x":0.089996337890625,"y":-0.11468505859375},{"x":0.1741790771484375,"y":0.08880615234375},{"x":0.2935638427734375,"y":0.1026763916015625},{"x":0.5280914306640625,"y":-0.1223602294921875},{"x":0.6283721923828125,"y":0.7561798095703125},{"x":-0.3906402587890625,"y":-0.1763916015625},{"x":-0.4280242919921875,"y":0.04010009765625},{"x":-0.3559722900390625,"y":-0.364227294921875},{"x":-0.499969482421875,"y":0.0830841064453125},{"x":-0.23291015625,"y":0.161834716796875},{"x":-0.0550537109375,"y":0.3111572265625},{"x":0.0990142822265625,"y":0.30199432373046875},{"x":-0.2371826171875,"y":-0.08917236328125},{"x":-0.192138671875,"y":0.101776123046875},{"x":-0.281707763671875,"y":-0.180023193359375},{"x":-0.30718994140625,"y":-0.0733489990234375},{"x":-0.26385498046875,"y":-0.115509033203125},{"x":0.14007568359375,"y":-0.2555999755859375},{"x":0.1855926513671875,"y":0.33553314208984375},{"x":-0.29876708984375,"y":-0.26727294921875},{"x":-0.342742919921875,"y":-0.113372802734375},{"x":-0.170166015625,"y":-0.282012939453125},{"x":-0.086883544921875,"y":-0.1011505126953125},{"x":-0.066314697265625,"y":-0.6963348388671875},{"x":-0.7939453125,"y":-0.174072265625},{"x":0.205078125,"y":-0.367279052734375},{"x":-0.23687744140625,"y":-0.108551025390625},{"x":0.098846435546875,"y":-0.289459228515625},{"x":0.02294921875,"y":-0.2686767578125},{"x":-0.118682861328125,"y":-0.2094573974609375},{"x":0.216339111328125,"y":-0.1840667724609375},{"x":0.112335205078125,"y":-0.4598388671875},{"x":0.3685302734375,"y":0.45406341552734375},{"x":-0.021087646484375,"y":0.261199951171875},{"x":0.164398193359375,"y":0.064208984375},{"x":0.075653076171875,"y":-0.2861328125},{"x":0.002410888671875,"y":-0.1258544921875},{"x":-0.016632080078125,"y":-0.4322967529296875},{"x":-0.10009765625,"y":-0.01689910888671875},{"x":-0.209503173828125,"y":0.14163970947265625},{"x":0.398590087890625,"y":0.108184814453125},{"x":0.30364990234375,"y":0.060546875},{"x":0.361541748046875,"y":-0.090911865234375},{"x":0.334564208984375,"y":-0.3388214111328125},{"x":0.581024169921875,"y":0.1868743896484375},{"x":0.337127685546875,"y":-0.37206268310546875},{"x":-0.142486572265625,"y":0.069793701171875}],"optimisedCameraToObject":{"translation":{"x":-0.12510669582274828,"y":0.04183069160430232,"z":0.41996907569857694},"rotation":{"quaternion":{"W":0.6449226582621468,"X":0.21061380686415473,"Y":0.20630520206875444,"Z":-0.7050920172698348}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img16.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":292.6556701660156,"y":346.8438415527344},{"x":291.2195129394531,"y":311.52203369140625},{"x":289.42340087890625,"y":277.18695068359375},{"x":287.3701171875,"y":242.94354248046875},{"x":285.6595458984375,"y":208.80947875976562},{"x":284.0600891113281,"y":175.249755859375},{"x":282.49786376953125,"y":142.0118408203125},{"x":319.8542175292969,"y":206.0668487548828},{"x":318.1240234375,"y":172.05056762695312},{"x":354.2065734863281,"y":202.96746826171875},{"x":395.9179992675781,"y":303.9895324707031},{"x":393.7587890625,"y":268.9156188964844},{"x":391.3592529296875,"y":234.1182861328125},{"x":433.9818420410156,"y":336.80792236328125},{"x":431.35906982421875,"y":301.2689208984375},{"x":429.1118469238281,"y":266.00115966796875},{"x":465.0064392089844,"y":262.53564453125},{"x":454.2035217285156,"y":124.86638641357422},{"x":497.9110412597656,"y":224.94482421875}],"reprojectionErrors":[{"x":0.18719482421875,"y":-0.018768310546875},{"x":-0.148895263671875,"y":0.30938720703125},{"x":-0.109466552734375,"y":0.005645751953125},{"x":0.20233154296875,"y":-0.041961669921875},{"x":0.186309814453125,"y":0.142059326171875},{"x":0.073822021484375,"y":0.0860443115234375},{"x":-0.061614990234375,"y":0.0360260009765625},{"x":0.06005859375,"y":-0.1759185791015625},{"x":-0.099365234375,"y":0.0829010009765625},{"x":0.094970703125,"y":-0.170684814453125},{"x":-0.0045166015625,"y":-0.09222412109375},{"x":-0.167572021484375,"y":-0.116302490234375},{"x":-0.06744384765625,"y":-0.0595855712890625},{"x":0.102020263671875,"y":0.0123291015625},{"x":0.18060302734375,"y":-0.072265625},{"x":-0.09027099609375,"y":-0.06005859375},{"x":-0.20611572265625,"y":0.51593017578125},{"x":0.003753662109375,"y":0.0922698974609375},{"x":0.134307861328125,"y":-0.02490234375}],"optimisedCameraToObject":{"translation":{"x":-0.0859687011288145,"y":0.04317990371736229,"z":0.49388014175986866},"rotation":{"quaternion":{"W":0.6809721844404659,"X":-0.06850751721922724,"Y":2.844330575625928E-4,"Z":-0.7290977459851821}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img17.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":248.2644805908203,"y":522.1775512695312},{"x":253.6488037109375,"y":480.0160217285156},{"x":258.24884033203125,"y":440.87060546875},{"x":262.91851806640625,"y":403.53814697265625},{"x":267.2861022949219,"y":369.3082275390625},{"x":270.9449157714844,"y":336.6900329589844},{"x":274.8834228515625,"y":306.0249938964844},{"x":292.2176513671875,"y":524.5216064453125},{"x":295.9043884277344,"y":482.364013671875},{"x":299.1519470214844,"y":443.5943603515625},{"x":302.7195739746094,"y":407.1409606933594},{"x":305.5068664550781,"y":372.4423828125},{"x":308.6120910644531,"y":340.17352294921875},{"x":310.996337890625,"y":309.4010925292969},{"x":335.04669189453125,"y":526.8685302734375},{"x":337.1209716796875,"y":485.2360534667969},{"x":339.4740905761719,"y":446.2716064453125},{"x":341.22125244140625,"y":409.4973449707031},{"x":343.1964111328125,"y":375.3641357421875},{"x":344.8797302246094,"y":342.9462585449219},{"x":346.45928955078125,"y":312.3656311035156},{"x":377.4754333496094,"y":529.5736083984375},{"x":378.1507263183594,"y":487.4531555175781},{"x":379.1223449707031,"y":449.06317138671875},{"x":379.9473876953125,"y":412.4307861328125},{"x":381.729248046875,"y":315.623779296875},{"x":419.4560546875,"y":532.0897216796875},{"x":418.776611328125,"y":490.45062255859375},{"x":418.24658203125,"y":451.7590026855469},{"x":417.5472106933594,"y":415.45849609375},{"x":416.5487976074219,"y":318.81982421875},{"x":457.0987548828125,"y":454.6529235839844},{"x":455.272216796875,"y":418.13555908203125},{"x":451.23333740234375,"y":321.9449157714844},{"x":495.2098388671875,"y":457.13616943359375},{"x":492.39215087890625,"y":421.14910888671875},{"x":485.1968688964844,"y":325.0225524902344}],"reprojectionErrors":[{"x":0.4127349853515625,"y":-0.3675537109375},{"x":0.0849456787109375,"y":-0.035430908203125},{"x":0.221343994140625,"y":-0.07781982421875},{"x":-0.0023193359375,"y":0.46380615234375},{"x":-0.188262939453125,"y":0.08447265625},{"x":0.093292236328125,"y":0.084716796875},{"x":-0.12567138671875,"y":-0.04571533203125},{"x":-0.0679931640625,"y":-0.2015380859375},{"x":-0.141510009765625,"y":0.311279296875},{"x":-0.002593994140625,"y":0.0499267578125},{"x":-0.38958740234375,"y":-0.154510498046875},{"x":-0.1837158203125,"y":0.047332763671875},{"x":-0.46697998046875,"y":-0.206878662109375},{"x":-0.18603515625,"y":-0.1502685546875},{"x":0.0091552734375,"y":-0.0772705078125},{"x":0.141357421875,"y":0.092987060546875},{"x":-0.142120361328125,"y":0.181640625},{"x":0.05609130859375,"y":0.42987060546875},{"x":-0.086944580078125,"y":0.178070068359375},{"x":-0.041656494140625,"y":0.167236328125},{"x":0.01263427734375,"y":0.111419677734375},{"x":-0.06536865234375,"y":-0.3489990234375},{"x":0.094390869140625,"y":0.489654541015625},{"x":-0.09234619140625,"y":0.157470703125},{"x":-0.17816162109375,"y":0.394500732421875},{"x":0.022003173828125,"y":0.035125732421875},{"x":-0.22979736328125,"y":-0.46868896484375},{"x":-0.052581787109375,"y":0.06689453125},{"x":0.008453369140625,"y":0.18841552734375},{"x":0.269134521484375,"y":0.223052978515625},{"x":0.10791015625,"y":-0.022552490234375},{"x":-0.08038330078125,"y":-0.018402099609375},{"x":0.15679931640625,"y":0.361419677734375},{"x":-0.036895751953125,"y":-0.05181884765625},{"x":0.12109375,"y":0.146636962890625},{"x":0.22515869140625,"y":0.12335205078125},{"x":0.181640625,"y":-0.0753173828125}],"optimisedCameraToObject":{"translation":{"x":-0.10235287419901502,"y":0.13493217304711758,"z":0.38643008972472376},"rotation":{"quaternion":{"W":0.6973547107894487,"X":-0.1519544065997854,"Y":-0.24016154936725514,"Z":-0.65797317259915}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img18.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":238.08660888671875,"y":508.70318603515625},{"x":244.47987365722656,"y":466.81884765625},{"x":250.92901611328125,"y":427.4059753417969},{"x":256.1715087890625,"y":390.6396179199219},{"x":261.4705505371094,"y":355.842041015625},{"x":266.37548828125,"y":323.2245178222656},{"x":271.19464111328125,"y":292.1780090332031},{"x":281.9936218261719,"y":512.49560546875},{"x":286.9651184082031,"y":470.708740234375},{"x":300.0958557128906,"y":360.31280517578125},{"x":303.9748229980469,"y":327.7957458496094},{"x":307.40814208984375,"y":296.79608154296875},{"x":324.89837646484375,"y":516.0947875976562},{"x":328.67437744140625,"y":474.3115539550781},{"x":340.2364807128906,"y":332.1391296386719},{"x":342.9891357421875,"y":301.0456237792969},{"x":367.3838195800781,"y":519.9173583984375},{"x":369.51348876953125,"y":478.34002685546875},{"x":371.3661804199219,"y":439.6559143066406},{"x":376.9237365722656,"y":336.32525634765625},{"x":378.4332275390625,"y":305.86614990234375},{"x":408.816650390625,"y":523.4966430664062},{"x":409.70263671875,"y":482.2052917480469},{"x":410.4468078613281,"y":443.74163818359375},{"x":411.2080383300781,"y":407.2328796386719},{"x":411.9972229003906,"y":373.1476135253906},{"x":412.6400451660156,"y":340.6640625},{"x":413.1956787109375,"y":310.0948486328125},{"x":450.4736022949219,"y":527.1973876953125},{"x":449.3086853027344,"y":485.83233642578125},{"x":449.1990051269531,"y":447.67498779296875},{"x":448.8748474121094,"y":411.359375},{"x":448.3907165527344,"y":377.24298095703125},{"x":448.1876525878906,"y":344.95098876953125},{"x":447.6660461425781,"y":314.3572692871094},{"x":488.9281311035156,"y":489.99053955078125},{"x":487.2498779296875,"y":451.450927734375},{"x":485.7583312988281,"y":415.2386169433594},{"x":484.3245849609375,"y":381.19354248046875}],"reprojectionErrors":[{"x":0.4192657470703125,"y":-0.249053955078125},{"x":0.306182861328125,"y":-0.104949951171875},{"x":-0.2501678466796875,"y":0.1378173828125},{"x":0.0477294921875,"y":0.071807861328125},{"x":-0.032318115234375,"y":0.1695556640625},{"x":-0.0123291015625,"y":0.03790283203125},{"x":-0.17620849609375,"y":0.1241455078125},{"x":0.0413818359375,"y":-0.20355224609375},{"x":-0.069976806640625,"y":0.0172119140625},{"x":-0.299285888671875,"y":0.07940673828125},{"x":-0.3583984375,"y":-0.069580078125},{"x":-0.17913818359375,"y":0.03753662109375},{"x":0.0361328125,"y":-0.0262451171875},{"x":-0.259979248046875,"y":0.363372802734375},{"x":0.1700439453125,"y":-0.01416015625},{"x":0.012542724609375,"y":0.254791259765625},{"x":-0.1624755859375,"y":-0.13226318359375},{"x":-0.154144287109375,"y":0.222412109375},{"x":0.003814697265625,"y":0.17095947265625},{"x":-0.17919921875,"y":0.135101318359375},{"x":-0.086578369140625,"y":-0.162200927734375},{"x":0.09521484375,"y":-0.0533447265625},{"x":0.042266845703125,"y":0.18475341796875},{"x":0.083587646484375,"y":0.055572509765625},{"x":0.06451416015625,"y":0.215118408203125},{"x":-0.02215576171875,"y":0.0028076171875},{"x":0.00115966796875,"y":0.0697021484375},{"x":0.07830810546875,"y":-0.04913330078125},{"x":-0.45172119140625,"y":-0.15264892578125},{"x":0.276885986328125,"y":0.32696533203125},{"x":-0.02069091796875,"y":0.0330810546875},{"x":-0.077239990234375,"y":0.11865234375},{"x":0.050445556640625,"y":0.0372314453125},{"x":-0.080657958984375,"y":-0.00439453125},{"x":0.127227783203125,"y":-0.030242919921875},{"x":-0.032806396484375,"y":-0.11895751953125},{"x":0.076751708984375,"y":0.1099853515625},{"x":0.093292236328125,"y":0.210723876953125},{"x":0.137847900390625,"y":0.15740966796875}],"optimisedCameraToObject":{"translation":{"x":-0.10858149773039413,"y":0.12622425131158024,"z":0.3854284247307382},"rotation":{"quaternion":{"W":0.7087367317898559,"X":-0.13810070463493856,"Y":-0.23986823524424022,"Z":-0.6489096008782591}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img19.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":154.96969604492188,"y":461.872802734375},{"x":156.29348754882812,"y":404.18939208984375},{"x":157.0758056640625,"y":351.90899658203125},{"x":157.9696502685547,"y":302.9683532714844},{"x":158.96658325195312,"y":257.94097900390625},{"x":159.43991088867188,"y":215.47271728515625},{"x":159.91456604003906,"y":176.17434692382812},{"x":212.7816925048828,"y":465.74603271484375},{"x":211.72991943359375,"y":410.862548828125},{"x":210.8527374267578,"y":360.7347717285156},{"x":209.67538452148438,"y":313.75164794921875},{"x":208.5023651123047,"y":270.1269836425781},{"x":207.87344360351562,"y":229.50213623046875},{"x":206.47793579101562,"y":191.16921997070312},{"x":264.91424560546875,"y":469.1167297363281},{"x":261.6494140625,"y":417.10968017578125},{"x":259.027587890625,"y":368.64984130859375},{"x":256.21527099609375,"y":323.6822814941406},{"x":253.8461456298828,"y":281.6233825683594},{"x":251.52481079101562,"y":241.94259643554688},{"x":248.95449829101562,"y":204.6619110107422},{"x":312.5733337402344,"y":472.6824951171875},{"x":307.9697570800781,"y":422.6612548828125},{"x":303.6177673339844,"y":376.37603759765625},{"x":299.8455505371094,"y":332.7850646972656},{"x":296.1270446777344,"y":291.972412109375},{"x":292.1070251464844,"y":253.361572265625},{"x":288.9207458496094,"y":217.49571228027344},{"x":355.6849060058594,"y":476.03814697265625},{"x":349.72247314453125,"y":427.5773620605469},{"x":344.2697448730469,"y":382.9139709472656},{"x":339.2030944824219,"y":340.7777099609375},{"x":334.2503967285156,"y":301.25445556640625},{"x":330.0426940917969,"y":264.14501953125},{"x":325.8037414550781,"y":229.42262268066406},{"x":395.5015563964844,"y":478.9344177246094},{"x":388.4141540527344,"y":432.2012634277344},{"x":382.2043151855469,"y":389.3100280761719},{"x":376.1065979003906,"y":348.737060546875},{"x":370.32110595703125,"y":310.1910095214844},{"x":364.78607177734375,"y":274.0994567871094},{"x":359.8312072753906,"y":240.00885009765625},{"x":432.1224670410156,"y":481.6935729980469},{"x":424.1741638183594,"y":436.66357421875},{"x":416.8729553222656,"y":395.08740234375},{"x":410.0345764160156,"y":355.71661376953125},{"x":403.8086242675781,"y":318.77581787109375},{"x":397.385498046875,"y":283.20733642578125},{"x":391.7206726074219,"y":250.20066833496094}],"reprojectionErrors":[{"x":0.286041259765625,"y":-0.413726806640625},{"x":-0.018707275390625,"y":0.23974609375},{"x":0.1456146240234375,"y":-0.092529296875},{"x":0.134185791015625,"y":0.155426025390625},{"x":-0.0376129150390625,"y":-0.01531982421875},{"x":0.262939453125,"y":0.3834686279296875},{"x":0.516082763671875,"y":0.42437744140625},{"x":-0.0541229248046875,"y":-0.077911376953125},{"x":-0.2412872314453125,"y":0.313873291015625},{"x":-0.5040435791015625,"y":-0.021942138671875},{"x":-0.3782958984375,"y":0.09197998046875},{"x":-0.177734375,"y":0.0682373046875},{"x":-0.4500579833984375,"y":-0.05804443359375},{"x":0.108489990234375,"y":0.1393890380859375},{"x":-0.095489501953125,"y":0.356719970703125},{"x":0.07403564453125,"y":0.194305419921875},{"x":-0.17254638671875,"y":0.172882080078125},{"x":-0.025115966796875,"y":-0.0330810546875},{"x":-0.1376495361328125,"y":-0.169891357421875},{"x":-0.1324615478515625,"y":0.005584716796875},{"x":0.2717742919921875,"y":0.2197723388671875},{"x":-0.3167724609375,"y":0.24713134765625},{"x":-0.341064453125,"y":0.23138427734375},{"x":-0.294830322265625,"y":-0.130706787109375},{"x":-0.538116455078125,"y":-0.133087158203125},{"x":-0.57269287109375,"y":-0.15252685546875},{"x":-0.0677490234375,"y":0.1309661865234375},{"x":-0.179901123046875,"y":-0.051483154296875},{"x":-0.042083740234375,"y":0.04364013671875},{"x":0.02313232421875,"y":0.432373046875},{"x":-0.028839111328125,"y":0.149749755859375},{"x":-0.111724853515625,"y":0.1683349609375},{"x":0.013824462890625,"y":0.14129638671875},{"x":-0.312103271484375,"y":0.0379638671875},{"x":-0.338775634765625,"y":-0.3180999755859375},{"x":-0.021697998046875,"y":0.033233642578125},{"x":0.114654541015625,"y":0.5106201171875},{"x":-0.182586669921875,"y":0.038116455078125},{"x":-0.188720703125,"y":-0.125762939453125},{"x":-0.139678955078125,"y":0.076629638671875},{"x":-0.00543212890625,"y":0.010894775390625},{"x":-0.143890380859375,"y":-0.0529632568359375},{"x":0.067840576171875,"y":-0.074676513671875},{"x":0.1888427734375,"y":0.38336181640625},{"x":0.143585205078125,"y":0.071014404296875},{"x":0.0738525390625,"y":-5.4931640625E-4},{"x":-0.207611083984375,"y":-0.265960693359375},{"x":0.0753173828125,"y":0.145721435546875},{"x":-0.062591552734375,"y":-0.121490478515625}],"optimisedCameraToObject":{"translation":{"x":-0.10931091276328657,"y":0.07397400768140748,"z":0.2569485460455027},"rotation":{"quaternion":{"W":0.655612448890124,"X":0.04817300888216331,"Y":-0.40449078767417546,"Z":-0.6357978301018795}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img20.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":100.80520629882812,"y":513.385009765625},{"x":102.07193756103516,"y":440.7701110839844},{"x":103.12223815917969,"y":373.23736572265625},{"x":104.5593032836914,"y":309.16888427734375},{"x":104.95926666259766,"y":249.9786834716797},{"x":105.28286743164062,"y":193.16815185546875},{"x":105.96147918701172,"y":140.13946533203125},{"x":161.85821533203125,"y":511.9703674316406},{"x":160.81402587890625,"y":444.7353210449219},{"x":160.1405792236328,"y":382.1991271972656},{"x":159.73500061035156,"y":323.0000915527344},{"x":158.92611694335938,"y":266.9617614746094},{"x":157.97793579101562,"y":213.9881591796875},{"x":156.98106384277344,"y":163.65074157714844},{"x":213.78196716308594,"y":511.306640625},{"x":211.44454956054688,"y":448.33380126953125},{"x":209.12344360351562,"y":389.87225341796875},{"x":207.26498413085938,"y":334.2403259277344},{"x":205.38333129882812,"y":281.8587646484375},{"x":203.26075744628906,"y":231.7283935546875},{"x":201.82568359375,"y":184.38002014160156},{"x":258.7056579589844,"y":510.115234375},{"x":255.1356201171875,"y":452.0194091796875},{"x":252.05642700195312,"y":396.7320556640625},{"x":248.97608947753906,"y":344.0758361816406},{"x":246.47476196289062,"y":294.976806640625},{"x":244.173583984375,"y":247.8833465576172},{"x":241.15284729003906,"y":202.45370483398438},{"x":297.76300048828125,"y":509.07550048828125},{"x":293.9688415527344,"y":454.1711120605469},{"x":290.08551025390625,"y":402.9107360839844},{"x":286.2107238769531,"y":353.1688232421875},{"x":282.9294738769531,"y":306.5528259277344},{"x":279.30596923828125,"y":261.2279052734375},{"x":276.0481262207031,"y":218.44834899902344},{"x":332.5775146484375,"y":508.4853515625},{"x":327.8035888671875,"y":456.8742370605469},{"x":323.4428405761719,"y":407.9340515136719},{"x":319.0947265625,"y":361.31298828125},{"x":315.0352783203125,"y":316.7378845214844},{"x":311.5171203613281,"y":273.8785095214844},{"x":363.2084655761719,"y":507.9447021484375},{"x":358.0156555175781,"y":459.1790466308594},{"x":353.1886291503906,"y":412.7841796875},{"x":348.7685241699219,"y":368.16290283203125},{"x":344.1642761230469,"y":325.7691345214844},{"x":339.9801330566406,"y":284.9371643066406}],"reprojectionErrors":[{"x":0.25543975830078125,"y":-0.26629638671875},{"x":0.0413055419921875,"y":0.0330810546875},{"x":-0.01116180419921875,"y":-0.123321533203125},{"x":-0.5000152587890625,"y":0.448760986328125},{"x":0.00313568115234375,"y":-0.0458831787109375},{"x":0.541534423828125,"y":0.5551605224609375},{"x":0.687347412109375,"y":0.5518341064453125},{"x":-0.28607177734375,"y":-0.016021728515625},{"x":-0.1202239990234375,"y":0.343597412109375},{"x":-0.260345458984375,"y":-0.0277099609375},{"x":-0.6092071533203125,"y":-0.1142578125},{"x":-0.5006256103515625,"y":-0.0465087890625},{"x":-0.2030792236328125,"y":-0.0015716552734375},{"x":0.1888580322265625,"y":0.205108642578125},{"x":-0.33953857421875,"y":-0.354278564453125},{"x":-0.296783447265625,"y":0.420623779296875},{"x":-0.13079833984375,"y":0.124969482421875},{"x":-0.29931640625,"y":0.15997314453125},{"x":-0.326629638671875,"y":-0.1458740234375},{"x":-0.004119873046875,"y":-0.0182952880859375},{"x":-0.2684326171875,"y":-0.1904449462890625},{"x":-0.299560546875,"y":-0.035003662109375},{"x":-0.072540283203125,"y":-0.072418212890625},{"x":-0.15069580078125,"y":0.093841552734375},{"x":-0.0562744140625,"y":0.41064453125},{"x":-0.382171630859375,"y":-0.255645751953125},{"x":-0.7611083984375,"y":-0.54083251953125},{"x":-0.2837982177734375,"y":-0.2728424072265625},{"x":-4.2724609375E-4,"y":0.23797607421875},{"x":-0.329559326171875,"y":0.574066162109375},{"x":-0.35638427734375,"y":-0.074798583984375},{"x":-0.1939697265625,"y":0.225128173828125},{"x":-0.44122314453125,"y":-0.307342529296875},{"x":-0.175018310546875,"y":0.0047607421875},{"x":-0.11474609375,"y":-0.2364654541015625},{"x":-0.072906494140625,"y":0.1480712890625},{"x":-0.004180908203125,"y":0.342926025390625},{"x":-0.120269775390625,"y":0.23150634765625},{"x":-0.03619384765625,"y":0.00433349609375},{"x":-0.042144775390625,"y":-0.212371826171875},{"x":-0.40374755859375,"y":-0.2225341796875},{"x":0.19512939453125,"y":0.080902099609375},{"x":0.2496337890625,"y":0.23724365234375},{"x":0.173828125,"y":0.139434814453125},{"x":-0.08868408203125,"y":0.24774169921875},{"x":0.039215087890625,"y":-0.017181396484375},{"x":-0.0594482421875,"y":-0.104583740234375}],"optimisedCameraToObject":{"translation":{"x":-0.1090467482372623,"y":0.08466989786255509,"z":0.21153653745773643},"rotation":{"quaternion":{"W":0.6339962075057909,"X":0.20073921310499568,"Y":-0.4444907011704959,"Z":-0.6001504759335132}}},"includeObservationInCalibration":true,"snapshotName":"img21.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/93ca5d50-4178-4bc6-a221-119a4088341d/imgs/800x600/img21.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/vision_settings/Camera Calibrations/5-800-600.json b/vision_settings/Camera Calibrations/5-800-600.json new file mode 100644 index 00000000..cab0af4f --- /dev/null +++ b/vision_settings/Camera Calibrations/5-800-600.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[683.7287187889929,0.0,400.30187267807327,0.0,683.7160523056789,278.4152661630601,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.0338977961854647,-0.002737908728178591,-6.737420973416729E-4,-9.789818803586793E-4,-0.12393062681002211,-0.0024618335935444706,-4.4745487060822285E-4,0.004908505043866199]},"calobjectWarp":[8.087711823720366E-5,1.1052918923795166E-4],"observations":[{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":359.4504699707031,"y":438.2180480957031},{"x":364.901611328125,"y":389.16510009765625},{"x":370.4822998046875,"y":340.9924621582031},{"x":375.718994140625,"y":294.2163391113281},{"x":380.78955078125,"y":248.00390625},{"x":385.80712890625,"y":202.62818908691406},{"x":390.9738464355469,"y":158.20205688476562},{"x":405.7803955078125,"y":445.019775390625},{"x":410.3164978027344,"y":393.8492736816406},{"x":415.8307189941406,"y":344.5982666015625},{"x":420.3523254394531,"y":296.39642333984375},{"x":425.3077087402344,"y":249.11329650878906},{"x":430.43341064453125,"y":203.19020080566406},{"x":434.3872985839844,"y":157.55783081054688},{"x":453.2738342285156,"y":451.5457458496094},{"x":458.7372131347656,"y":399.3810119628906},{"x":462.78497314453125,"y":348.9298095703125},{"x":467.5816650390625,"y":299.3102722167969},{"x":471.63836669921875,"y":250.7702178955078},{"x":475.9518737792969,"y":203.17205810546875},{"x":480.2718200683594,"y":156.5410919189453},{"x":504.4382629394531,"y":459.09234619140625},{"x":508.6658020019531,"y":404.7486572265625},{"x":513.0097045898438,"y":353.0032653808594},{"x":516.9269409179688,"y":301.935302734375},{"x":521.0410766601562,"y":252.01223754882812},{"x":525.0520629882812,"y":203.26498413085938},{"x":528.3720092773438,"y":155.7746124267578},{"x":558.0979614257812,"y":465.98565673828125},{"x":562.0592041015625,"y":411.1893615722656},{"x":565.7212524414062,"y":357.9281311035156},{"x":568.9844970703125,"y":304.8802795410156},{"x":572.591796875,"y":253.92079162597656},{"x":575.896484375,"y":203.69337463378906},{"x":579.3670654296875,"y":154.26283264160156},{"x":615.6222534179688,"y":474.88330078125},{"x":618.552734375,"y":417.2928161621094},{"x":621.396484375,"y":362.5422668457031},{"x":624.4762573242188,"y":307.9018249511719},{"x":627.2247314453125,"y":255.8129425048828},{"x":630.485107421875,"y":203.65341186523438},{"x":633.45751953125,"y":153.42515563964844},{"x":676.164306640625,"y":483.3771057128906},{"x":678.5150146484375,"y":424.4207763671875},{"x":680.7987060546875,"y":367.2778625488281},{"x":683.0733642578125,"y":311.6180725097656},{"x":685.4827270507812,"y":257.1268310546875},{"x":687.64013671875,"y":203.97341918945312},{"x":690.2258911132812,"y":151.71176147460938}],"reprojectionErrors":[{"x":0.179443359375,"y":0.46759033203125},{"x":0.284393310546875,"y":0.245361328125},{"x":0.130035400390625,"y":0.20635986328125},{"x":0.19464111328125,"y":-0.204437255859375},{"x":0.30474853515625,"y":-0.1912384033203125},{"x":0.351531982421875,"y":-0.062286376953125},{"x":0.136871337890625,"y":0.035888671875},{"x":-0.3680419921875,"y":0.08294677734375},{"x":0.282073974609375,"y":0.63189697265625},{"x":-0.169219970703125,"y":0.382110595703125},{"x":0.253326416015625,"y":0.162078857421875},{"x":0.127685546875,"y":0.062408447265625},{"x":-0.278533935546875,"y":-0.3960418701171875},{"x":0.38067626953125,"y":-0.1800994873046875},{"x":0.370269775390625,"y":0.3206787109375},{"x":-0.3243408203125,"y":0.439483642578125},{"x":0.281280517578125,"y":0.027557373046875},{"x":0.026947021484375,"y":-0.07843017578125},{"x":0.40576171875,"y":-0.1691436767578125},{"x":0.42486572265625,"y":-0.1478271484375},{"x":0.338348388671875,"y":-0.07861328125},{"x":0.097412109375,"y":-0.085784912109375},{"x":0.1671142578125,"y":0.702606201171875},{"x":0.0147705078125,"y":0.1429443359375},{"x":0.18756103515625,"y":0.10723876953125},{"x":0.06573486328125,"y":0.0816802978515625},{"x":-0.04693603515625,"y":-0.0086822509765625},{"x":0.4410400390625,"y":-0.28680419921875},{"x":0.22454833984375,"y":0.570770263671875},{"x":0.02740478515625,"y":0.2095947265625},{"x":0.03570556640625,"y":-0.362884521484375},{"x":0.35260009765625,"y":0.122039794921875},{"x":0.23895263671875,"y":-0.260833740234375},{"x":0.3447265625,"y":-0.2028350830078125},{"x":0.20458984375,"y":0.186004638671875},{"x":-0.35382080078125,"y":-0.3299560546875},{"x":-0.12359619140625,"y":0.3992919921875},{"x":0.1138916015625,"y":-0.30731201171875},{"x":0.03912353515625,"y":0.22247314453125},{"x":0.2225341796875,"y":-0.5073699951171875},{"x":-0.17620849609375,"y":0.073760986328125},{"x":-0.35443115234375,"y":-0.08502197265625},{"x":-0.493896484375,"y":-0.3377685546875},{"x":-0.36785888671875,"y":-0.057952880859375},{"x":-0.23687744140625,"y":-0.099517822265625},{"x":-0.1563720703125,"y":-0.194915771484375},{"x":-0.267578125,"y":-0.08892822265625},{"x":-0.18145751953125,"y":-0.0069580078125},{"x":-0.576171875,"y":0.4438934326171875}],"optimisedCameraToObject":{"translation":{"x":-0.047520973861772446,"y":0.10704648206564611,"z":0.36014430049059043},"rotation":{"quaternion":{"W":0.7194662375514504,"X":-0.1871250948794475,"Y":0.06637060952104393,"Z":-0.6655429919109078}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":274.34320068359375,"y":442.9385986328125},{"x":277.8537292480469,"y":392.5818786621094},{"x":280.3214416503906,"y":343.51812744140625},{"x":283.3377990722656,"y":295.751708984375},{"x":286.3088073730469,"y":248.92352294921875},{"x":289.02081298828125,"y":202.76614379882812},{"x":291.3138732910156,"y":157.7633056640625},{"x":321.5418701171875,"y":445.55816650390625},{"x":324.1218566894531,"y":394.0966796875},{"x":326.8875732421875,"y":344.30816650390625},{"x":329.5586853027344,"y":295.84417724609375},{"x":331.201171875,"y":248.20689392089844},{"x":333.7942810058594,"y":201.46795654296875},{"x":335.885009765625,"y":155.97525024414062},{"x":370.0249328613281,"y":447.86865234375},{"x":372.067138671875,"y":395.9233703613281},{"x":373.8126525878906,"y":345.1901550292969},{"x":375.96624755859375,"y":295.736083984375},{"x":377.3988952636719,"y":247.21795654296875},{"x":379.5448303222656,"y":200.01986694335938},{"x":381.42242431640625,"y":153.90682983398438},{"x":420.4212951660156,"y":450.7254333496094},{"x":421.9056091308594,"y":397.3519592285156},{"x":423.08135986328125,"y":346.138427734375},{"x":424.3227233886719,"y":295.69549560546875},{"x":425.788330078125,"y":246.75442504882812},{"x":427.2333984375,"y":198.5848846435547},{"x":428.0634460449219,"y":151.52215576171875},{"x":472.2633056640625,"y":453.2150573730469},{"x":472.9416809082031,"y":399.69488525390625},{"x":473.7998046875,"y":346.8320617675781},{"x":474.68109130859375,"y":295.72625732421875},{"x":475.22845458984375,"y":245.8820343017578},{"x":476.0465393066406,"y":196.9744415283203},{"x":476.67572021484375,"y":148.81947326660156},{"x":526.4703979492188,"y":456.36138916015625},{"x":526.1361694335938,"y":400.85479736328125},{"x":526.546875,"y":348.0179748535156},{"x":526.6170043945312,"y":295.68450927734375},{"x":526.5778198242188,"y":245.27850341796875},{"x":526.741943359375,"y":194.97412109375},{"x":527.000244140625,"y":146.73622131347656},{"x":582.0992431640625,"y":459.3163146972656},{"x":581.5538940429688,"y":403.3206481933594},{"x":580.7714233398438,"y":349.0279235839844},{"x":580.1444091796875,"y":295.90045166015625},{"x":579.6979370117188,"y":244.05404663085938},{"x":579.1796264648438,"y":193.47802734375},{"x":578.889404296875,"y":143.8227996826172}],"reprojectionErrors":[{"x":0.3812255859375,"y":-0.079254150390625},{"x":-0.110565185546875,"y":0.102203369140625},{"x":0.361846923828125,"y":0.131317138671875},{"x":0.2099609375,"y":-0.039825439453125},{"x":0.030548095703125,"y":-0.0934906005859375},{"x":0.039947509765625,"y":0.1983642578125},{"x":0.400634765625,"y":0.3145751953125},{"x":0.13037109375,"y":-0.22076416015625},{"x":0.069244384765625,"y":0.21148681640625},{"x":-0.244293212890625,"y":0.14971923828125},{"x":-0.527374267578125,"y":-0.103240966796875},{"x":0.156463623046875,"y":-0.09295654296875},{"x":-0.169769287109375,"y":0.0677642822265625},{"x":-0.050872802734375,"y":-0.008148193359375},{"x":0.173858642578125,"y":0.033355712890625},{"x":0.115234375,"y":0.063262939453125},{"x":0.299835205078125,"y":0.1004638671875},{"x":0.02496337890625,"y":0.029998779296875},{"x":0.421630859375,"y":0.1496124267578125},{"x":0.057403564453125,"y":0.0320892333984375},{"x":-0.084259033203125,"y":-0.1286163330078125},{"x":-0.027862548828125,"y":-0.1673583984375},{"x":-0.102264404296875,"y":0.37054443359375},{"x":0.093109130859375,"y":0.010498046875},{"x":0.185546875,"y":0.09161376953125},{"x":0.01788330078125,"y":-0.165130615234375},{"x":-0.163726806640625,"y":-0.0745849609375},{"x":0.23651123046875,"y":-0.0150299072265625},{"x":0.0889892578125,"y":0.0958251953125},{"x":0.20526123046875,"y":-0.175811767578125},{"x":0.119140625,"y":0.2022705078125},{"x":-0.011810302734375,"y":0.07757568359375},{"x":0.170257568359375,"y":-0.1046142578125},{"x":0.06158447265625,"y":-0.0667877197265625},{"x":0.12255859375,"y":0.3299713134765625},{"x":-0.2913818359375,"y":-0.195343017578125},{"x":0.1768798828125,"y":0.525054931640625},{"x":-0.1043701171875,"y":-0.069610595703125},{"x":-0.04949951171875,"y":0.131500244140625},{"x":0.1103515625,"y":-0.34844970703125},{"x":0.0628662109375,"y":0.26654052734375},{"x":-0.08282470703125,"y":-0.0357208251953125},{"x":-0.11376953125,"y":-0.18658447265625},{"x":-0.14422607421875,"y":-0.01202392578125},{"x":0.0777587890625,"y":-0.13519287109375},{"x":0.158935546875,"y":-0.0770263671875},{"x":0.07366943359375,"y":-0.0088043212890625},{"x":0.07379150390625,"y":0.0277252197265625},{"x":-0.14129638671875,"y":0.332427978515625}],"optimisedCameraToObject":{"translation":{"x":-0.08998321249659012,"y":0.10953707526097989,"z":0.35235474111237436},"rotation":{"quaternion":{"W":0.7048325011177542,"X":-0.1384183391577826,"Y":0.02315253794465801,"Z":-0.6953527656805668}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":82.23404693603516,"y":461.3736267089844},{"x":82.28726959228516,"y":406.0531921386719},{"x":82.0471420288086,"y":352.8470764160156},{"x":81.94580841064453,"y":300.1720275878906},{"x":81.66708374023438,"y":248.92205810546875},{"x":81.22974395751953,"y":198.0646514892578},{"x":81.00782775878906,"y":148.79647827148438},{"x":137.54762268066406,"y":456.8381652832031},{"x":136.78759765625,"y":402.6806640625},{"x":135.8144073486328,"y":349.55389404296875},{"x":135.320556640625,"y":297.0934143066406},{"x":134.5899200439453,"y":245.6873321533203},{"x":133.77630615234375,"y":195.48280334472656},{"x":132.78529357910156,"y":146.09207153320312},{"x":191.4954376220703,"y":453.3014221191406},{"x":190.492919921875,"y":398.6103210449219},{"x":189.2921600341797,"y":345.8428955078125},{"x":187.67872619628906,"y":294.083740234375},{"x":186.73768615722656,"y":242.90794372558594},{"x":185.3194122314453,"y":192.5492401123047},{"x":183.94471740722656,"y":143.466552734375},{"x":245.5373992919922,"y":449.7761535644531},{"x":244.06039428710938,"y":395.1517639160156},{"x":242.26646423339844,"y":342.1056213378906},{"x":240.84259033203125,"y":290.6866455078125},{"x":238.54953002929688,"y":239.79859924316406},{"x":236.80198669433594,"y":189.39804077148438},{"x":235.03158569335938,"y":140.9888458251953},{"x":299.2664794921875,"y":445.5015869140625},{"x":296.85894775390625,"y":391.70428466796875},{"x":294.88812255859375,"y":338.7549133300781},{"x":292.7428894042969,"y":286.8502197265625},{"x":290.18194580078125,"y":236.66351318359375},{"x":287.6996154785156,"y":186.98426818847656},{"x":285.23358154296875,"y":138.15565490722656},{"x":352.6754150390625,"y":441.7946472167969},{"x":349.6997985839844,"y":387.72186279296875},{"x":346.8805236816406,"y":335.28106689453125},{"x":343.8739929199219,"y":283.4638366699219},{"x":341.2309875488281,"y":233.80792236328125},{"x":338.769287109375,"y":183.8889617919922},{"x":335.83868408203125,"y":135.39999389648438},{"x":405.6952819824219,"y":438.1417541503906},{"x":402.14825439453125,"y":384.09759521484375},{"x":398.68035888671875,"y":331.9251403808594},{"x":395.2964782714844,"y":280.8402404785156},{"x":391.9171447753906,"y":230.29734802246094},{"x":388.68829345703125,"y":181.05270385742188},{"x":385.1523132324219,"y":132.09324645996094}],"reprojectionErrors":[{"x":0.46949005126953125,"y":-0.24249267578125},{"x":0.2147064208984375,"y":0.293701171875},{"x":0.2458038330078125,"y":-0.130584716796875},{"x":0.13083648681640625,"y":0.025604248046875},{"x":0.18619537353515625,"y":-0.172088623046875},{"x":0.39328765869140625,"y":0.2704620361328125},{"x":0.37825775146484375,"y":0.11993408203125},{"x":-0.0440521240234375,"y":0.341949462890625},{"x":-0.0665130615234375,"y":-0.05352783203125},{"x":0.1310577392578125,"y":-0.334808349609375},{"x":-0.1441192626953125,"y":-0.179351806640625},{"x":-0.176239013671875,"y":-0.015167236328125},{"x":-0.119354248046875,"y":-0.0273895263671875},{"x":0.1206512451171875,"y":0.135406494140625},{"x":0.41644287109375,"y":-0.040435791015625},{"x":0.0635986328125,"y":0.3240966796875},{"x":-0.070037841796875,"y":-0.098876953125},{"x":0.229156494140625,"y":-0.43536376953125},{"x":-0.1246795654296875,"y":-0.2999420166015625},{"x":0.01739501953125,"y":0.0360260009765625},{"x":0.1338348388671875,"y":0.077667236328125},{"x":0.4040374755859375,"y":-0.403350830078125},{"x":-0.0394134521484375,"y":0.116058349609375},{"x":-0.131195068359375,"y":0.18487548828125},{"x":-0.559539794921875,"y":-0.286773681640625},{"x":-0.0864715576171875,"y":-0.24176025390625},{"x":-0.127838134765625,"y":0.3260955810546875},{"x":-0.116424560546875,"y":-0.1226806640625},{"x":0.338470458984375,"y":0.01300048828125},{"x":0.26788330078125,"y":-0.077789306640625},{"x":-0.191070556640625,"y":0.102874755859375},{"x":-0.4290771484375,"y":0.317657470703125},{"x":-0.20654296875,"y":-0.14544677734375},{"x":-0.01934814453125,"y":-0.11279296875},{"x":0.193267822265625,"y":0.0371856689453125},{"x":0.2393798828125,"y":-0.10919189453125},{"x":0.1864013671875,"y":0.287750244140625},{"x":0.0386962890625,"y":0.164031982421875},{"x":0.137664794921875,"y":0.48785400390625},{"x":-0.069671630859375,"y":-0.3168182373046875},{"x":-0.403076171875,"y":0.1378173828125},{"x":-0.21429443359375,"y":0.123809814453125},{"x":0.1878662109375,"y":-0.257293701171875},{"x":0.162689208984375,"y":0.318756103515625},{"x":0.133056640625,"y":0.126556396484375},{"x":0.0914306640625,"y":-0.08953857421875},{"x":0.114715576171875,"y":0.1780242919921875},{"x":0.054473876953125,"y":0.1368255615234375},{"x":0.36602783203125,"y":0.7653350830078125}],"optimisedCameraToObject":{"translation":{"x":-0.1729166546294889,"y":0.11255501946075493,"z":0.3167835520258046},"rotation":{"quaternion":{"W":0.6821215424873076,"X":-0.03471990994311002,"Y":-0.062050821978042375,"Z":-0.7277736080816121}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":83.07823181152344,"y":517.118408203125},{"x":87.88838958740234,"y":460.3502197265625},{"x":92.66829681396484,"y":405.9388427734375},{"x":97.39484405517578,"y":353.4697265625},{"x":101.61882781982422,"y":303.8973388671875},{"x":106.16647338867188,"y":255.48318481445312},{"x":138.42564392089844,"y":514.49365234375},{"x":142.5609893798828,"y":458.1015625},{"x":146.28646850585938,"y":403.2303771972656},{"x":149.95643615722656,"y":351.91778564453125},{"x":153.39129638671875,"y":301.54327392578125},{"x":156.366943359375,"y":254.0829620361328},{"x":193.83897399902344,"y":512.6064453125},{"x":196.802734375,"y":455.8905944824219},{"x":199.26783752441406,"y":401.53277587890625},{"x":201.8685302734375,"y":349.77801513671875},{"x":203.96343994140625,"y":299.9927978515625},{"x":206.1278533935547,"y":252.13380432128906},{"x":249.71180725097656,"y":510.31072998046875},{"x":251.14382934570312,"y":453.3887023925781},{"x":252.765625,"y":399.677978515625},{"x":253.69598388671875,"y":347.74237060546875},{"x":254.8543243408203,"y":297.9603271484375},{"x":255.79820251464844,"y":250.96609497070312},{"x":304.6482849121094,"y":507.6640319824219},{"x":304.6331481933594,"y":451.4400329589844},{"x":304.8464050292969,"y":397.1972351074219},{"x":305.09588623046875,"y":345.8313293457031},{"x":305.1431579589844,"y":296.1461486816406},{"x":305.1734924316406,"y":248.92442321777344},{"x":359.348388671875,"y":505.4377746582031},{"x":358.08154296875,"y":449.2836608886719},{"x":357.100830078125,"y":395.0250549316406},{"x":356.51263427734375,"y":343.86627197265625},{"x":355.16485595703125,"y":294.2142333984375},{"x":354.2796936035156,"y":247.22035217285156},{"x":413.5896301269531,"y":503.2823181152344},{"x":411.5445251464844,"y":447.0349426269531},{"x":409.27044677734375,"y":393.0799560546875},{"x":407.0041198730469,"y":341.8686828613281},{"x":404.882080078125,"y":292.81109619140625},{"x":403.0477294921875,"y":245.4176483154297}],"reprojectionErrors":[{"x":-0.0475616455078125,"y":0.12811279296875},{"x":0.28946685791015625,"y":-0.225830078125},{"x":0.41347503662109375,"y":-0.366668701171875},{"x":0.364166259765625,"y":-0.055633544921875},{"x":0.6058731079101562,"y":-0.40716552734375},{"x":0.326171875,"y":0.17108154296875},{"x":0.389068603515625,"y":0.38018798828125},{"x":0.10772705078125,"y":-0.178863525390625},{"x":0.0536346435546875,"y":0.298187255859375},{"x":-0.1151123046875,"y":-0.40087890625},{"x":-0.207611083984375,"y":0.185516357421875},{"x":0.0106048583984375,"y":-0.0639190673828125},{"x":0.51678466796875,"y":-0.093994140625},{"x":0.12481689453125,"y":-0.162322998046875},{"x":0.1088104248046875,"y":-0.044158935546875},{"x":-0.1571502685546875,"y":-0.157958984375},{"x":-0.0240936279296875,"y":-0.028045654296875},{"x":-0.0603790283203125,"y":0.24462890625},{"x":-0.0474395751953125,"y":-0.148895263671875},{"x":-0.179412841796875,"y":0.15203857421875},{"x":-0.5646514892578125,"y":-0.22601318359375},{"x":-0.317657470703125,"y":-0.019073486328125},{"x":-0.35394287109375,"y":0.23748779296875},{"x":-0.227447509765625,"y":-0.23388671875},{"x":0.102691650390625,"y":0.157562255859375},{"x":0.156097412109375,"y":-0.080322265625},{"x":-0.02386474609375,"y":0.2210693359375},{"x":-0.244720458984375,"y":-0.005035400390625},{"x":-0.2677001953125,"y":0.281585693359375},{"x":-0.27783203125,"y":0.1557464599609375},{"x":0.277435302734375,"y":0.05352783203125},{"x":0.33026123046875,"y":-0.098876953125},{"x":0.149810791015625,"y":0.362213134765625},{"x":-0.373809814453125,"y":0.0625},{"x":-0.091827392578125,"y":0.44000244140625},{"x":-0.229400634765625,"y":0.20172119140625},{"x":0.70941162109375,"y":-0.11181640625},{"x":0.297149658203125,"y":-0.01934814453125},{"x":0.224029541015625,"y":0.27862548828125},{"x":0.245880126953125,"y":0.1617431640625},{"x":0.219390869140625,"y":0.066009521484375},{"x":-0.00506591796875,"y":0.3401031494140625}],"optimisedCameraToObject":{"translation":{"x":-0.16910077103914783,"y":0.15911943106387721,"z":0.29858676241512927},"rotation":{"quaternion":{"W":0.6859176166517411,"X":-0.0974571826677633,"Y":-0.1110047747004603,"Z":-0.7125286385170476}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":239.2843017578125,"y":440.5931396484375},{"x":238.03094482421875,"y":406.8934020996094},{"x":236.97119140625,"y":370.9664001464844},{"x":235.70620727539062,"y":333.0478515625},{"x":233.9529266357422,"y":292.9733581542969},{"x":232.124755859375,"y":250.71629333496094},{"x":230.8272705078125,"y":205.14633178710938},{"x":281.74859619140625,"y":437.7801208496094},{"x":281.8988037109375,"y":404.0287780761719},{"x":281.9566955566406,"y":368.76898193359375},{"x":281.9018859863281,"y":331.30072021484375},{"x":281.862548828125,"y":291.93646240234375},{"x":281.8541259765625,"y":249.80029296875},{"x":281.751708984375,"y":205.214111328125},{"x":323.0990905761719,"y":434.8944091796875},{"x":324.34454345703125,"y":401.3382263183594},{"x":325.18499755859375,"y":366.8199157714844},{"x":326.6962890625,"y":329.96295166015625},{"x":327.9823303222656,"y":291.14654541015625},{"x":329.1304931640625,"y":249.53404235839844},{"x":330.8140563964844,"y":205.47837829589844},{"x":363.8199768066406,"y":432.1268005371094},{"x":365.820068359375,"y":399.0633544921875},{"x":368.0506591796875,"y":364.6899719238281},{"x":370.2680969238281,"y":328.21490478515625},{"x":372.8559265136719,"y":289.9798583984375},{"x":375.6517639160156,"y":249.0879669189453},{"x":378.4981384277344,"y":205.962646484375},{"x":402.88525390625,"y":429.574462890625},{"x":406.08135986328125,"y":396.993896484375},{"x":409.211669921875,"y":362.94091796875},{"x":412.56744384765625,"y":327.07098388671875},{"x":416.5600280761719,"y":288.7976989746094},{"x":420.23095703125,"y":248.86036682128906},{"x":424.836669921875,"y":206.14993286132812},{"x":441.22430419921875,"y":427.0315246582031},{"x":445.29534912109375,"y":394.9856872558594},{"x":449.3189392089844,"y":361.66796875},{"x":454.33197021484375,"y":325.6158447265625},{"x":458.9430236816406,"y":288.2310791015625},{"x":464.3647766113281,"y":248.27978515625},{"x":470.00531005859375,"y":206.13009643554688},{"x":478.8186950683594,"y":424.9732360839844},{"x":483.6066589355469,"y":392.9191589355469},{"x":488.8572692871094,"y":359.4911804199219},{"x":494.6001892089844,"y":324.4992980957031},{"x":500.5210266113281,"y":287.2608947753906},{"x":506.89300537109375,"y":248.07981872558594},{"x":513.5761108398438,"y":206.1139373779297}],"reprojectionErrors":[{"x":0.269775390625,"y":-0.48284912109375},{"x":0.30523681640625,"y":-0.49798583984375},{"x":0.076690673828125,"y":-0.210693359375},{"x":-0.0233917236328125,"y":-0.030914306640625},{"x":0.2808837890625,"y":0.009735107421875},{"x":0.568023681640625,"y":-0.283172607421875},{"x":0.2233123779296875,"y":-0.0298004150390625},{"x":0.0906982421875,"y":-0.46240234375},{"x":-0.09564208984375,"y":-0.07330322265625},{"x":-0.1907958984375,"y":-0.055389404296875},{"x":-0.174530029296875,"y":0.1234130859375},{"x":-0.17510986328125,"y":-0.03790283203125},{"x":-0.20806884765625,"y":0.1241912841796875},{"x":-0.14874267578125,"y":0.047637939453125},{"x":-0.00787353515625,"y":-0.281982421875},{"x":-0.16552734375,"y":0.2568359375},{"x":0.144866943359375,"y":-0.078369140625},{"x":-0.147003173828125,"y":-0.07293701171875},{"x":-0.1387939453125,"y":-0.28765869140625},{"x":0.089111328125,"y":-0.0899658203125},{"x":-0.128662109375,"y":-0.0632781982421875},{"x":-0.46826171875,"y":-0.135894775390625},{"x":-0.31103515625,"y":0.24755859375},{"x":-0.26177978515625,"y":0.146728515625},{"x":-0.066162109375,"y":0.1971435546875},{"x":-0.09576416015625,"y":-0.117706298828125},{"x":-0.174835205078125,"y":-0.0973052978515625},{"x":-0.13079833984375,"y":-0.3863983154296875},{"x":-0.224700927734375,"y":-0.124542236328125},{"x":-0.24530029296875,"y":0.106109619140625},{"x":-0.022308349609375,"y":0.05535888671875},{"x":0.168212890625,"y":-0.083038330078125},{"x":-0.0679931640625,"y":0.10882568359375},{"x":0.2467041015625,"y":-0.29730224609375},{"x":-0.122589111328125,"y":-0.4050445556640625},{"x":-0.16900634765625,"y":-0.045166015625},{"x":-0.094635009765625,"y":-0.026214599609375},{"x":0.25616455078125,"y":-0.450286865234375},{"x":-0.134063720703125,"y":-3.662109375E-4},{"x":0.147735595703125,"y":-0.24078369140625},{"x":-0.0867919921875,"y":-0.1195831298828125},{"x":-0.21844482421875,"y":-0.2093505859375},{"x":-0.24700927734375,"y":-0.3759765625},{"x":0.034759521484375,"y":-0.032623291015625},{"x":0.130401611328125,"y":0.00732421875},{"x":0.03338623046875,"y":-0.206787109375},{"x":0.083953857421875,"y":-0.149078369140625},{"x":0.037750244140625,"y":-0.29876708984375},{"x":0.0672607421875,"y":-0.0104217529296875}],"optimisedCameraToObject":{"translation":{"x":-0.12470064196594709,"y":0.12165047699049457,"z":0.42254075577778183},"rotation":{"quaternion":{"W":0.6944651809787867,"X":0.23663163218027713,"Y":0.09209315332635794,"Z":-0.6732328231527389}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":290.4456787109375,"y":505.37762451171875},{"x":290.486572265625,"y":469.94757080078125},{"x":290.6847229003906,"y":432.260498046875},{"x":290.77740478515625,"y":392.8623962402344},{"x":290.96240234375,"y":351.1181640625},{"x":290.8155212402344,"y":306.8678894042969},{"x":291.1670837402344,"y":259.67510986328125},{"x":335.1721496582031,"y":503.1505432128906},{"x":336.5281677246094,"y":467.99456787109375},{"x":337.90045166015625,"y":431.0999450683594},{"x":339.5148010253906,"y":391.9068908691406},{"x":340.8893737792969,"y":350.6632080078125},{"x":342.4657287597656,"y":306.4918518066406},{"x":344.2222595214844,"y":260.14410400390625},{"x":379.10614013671875,"y":501.4327392578125},{"x":381.78424072265625,"y":466.0784912109375},{"x":383.9807434082031,"y":429.6075439453125},{"x":386.9366149902344,"y":390.92022705078125},{"x":389.2818298339844,"y":349.703857421875},{"x":392.6697998046875,"y":306.56317138671875},{"x":395.60479736328125,"y":260.26220703125},{"x":422.1651611328125,"y":499.28594970703125},{"x":425.70245361328125,"y":464.8080139160156},{"x":428.9243469238281,"y":428.6919250488281},{"x":433.29443359375,"y":389.9224853515625},{"x":437.3985290527344,"y":349.4651184082031},{"x":442.0696716308594,"y":306.65155029296875},{"x":446.1141052246094,"y":261.28643798828125},{"x":464.1915588378906,"y":497.9202880859375},{"x":468.6603088378906,"y":463.11334228515625},{"x":473.65435791015625,"y":427.1279602050781},{"x":479.0120849609375,"y":389.12738037109375},{"x":484.2682189941406,"y":349.099365234375},{"x":489.60589599609375,"y":306.7716369628906},{"x":496.1875,"y":261.4052429199219},{"x":505.9458312988281,"y":496.0772399902344},{"x":511.4469299316406,"y":461.8752746582031},{"x":517.1197509765625,"y":426.123291015625},{"x":523.7207641601562,"y":388.34271240234375},{"x":530.076904296875,"y":349.0098571777344},{"x":537.7286987304688,"y":306.8487548828125},{"x":544.7958374023438,"y":261.9919738769531},{"x":546.611083984375,"y":494.4787902832031},{"x":553.0819702148438,"y":460.65728759765625},{"x":560.136474609375,"y":425.1240539550781},{"x":567.474609375,"y":387.9979553222656},{"x":575.3368530273438,"y":348.388427734375},{"x":583.2337036132812,"y":306.8963317871094},{"x":592.8544311523438,"y":262.6622009277344}],"reprojectionErrors":[{"x":0.294586181640625,"y":-0.59234619140625},{"x":0.27947998046875,"y":-0.478363037109375},{"x":0.10821533203125,"y":-0.0863037109375},{"x":0.043670654296875,"y":-0.1385498046875},{"x":-0.111846923828125,"y":-0.197998046875},{"x":0.06597900390625,"y":-0.327667236328125},{"x":-0.253021240234375,"y":-0.343170166015625},{"x":0.1619873046875,"y":-0.27508544921875},{"x":0.0439453125,"y":-0.14215087890625},{"x":-0.019989013671875,"y":-0.21331787109375},{"x":-0.24945068359375,"y":-0.100189208984375},{"x":-0.15557861328125,"y":-0.242767333984375},{"x":-0.172119140625,"y":0.019866943359375},{"x":-0.2686767578125,"y":-0.3076171875},{"x":-0.0150146484375,"y":-0.40911865234375},{"x":-0.288848876953125,"y":0.20953369140625},{"x":0.054595947265625,"y":0.037261962890625},{"x":-0.213836669921875,"y":0.007080078125},{"x":0.2891845703125,"y":0.245086669921875},{"x":-0.074859619140625,"y":-0.063140869140625},{"x":0.20654296875,"y":0.08197021484375},{"x":-0.125335693359375,"y":-0.05804443359375},{"x":-0.1357421875,"y":-0.033660888671875},{"x":0.3665771484375,"y":-0.244720458984375},{"x":-0.06500244140625,"y":0.161956787109375},{"x":0.002838134765625,"y":0.039581298828125},{"x":-0.241546630859375,"y":-0.14691162109375},{"x":0.419708251953125,"y":-0.431365966796875},{"x":0.016082763671875,"y":-0.433685302734375},{"x":0.155303955078125,"y":0.19647216796875},{"x":0.024658203125,"y":0.16448974609375},{"x":-0.1923828125,"y":0.14947509765625},{"x":-0.006072998046875,"y":-0.01251220703125},{"x":0.42779541015625,"y":-0.24664306640625},{"x":-0.0223388671875,"y":-0.036163330078125},{"x":-0.325103759765625,"y":-0.279266357421875},{"x":-0.176727294921875,"y":0.017547607421875},{"x":0.1102294921875,"y":0.05584716796875},{"x":-0.19439697265625,"y":0.1607666015625},{"x":0.1119384765625,"y":-0.3153076171875},{"x":-0.47857666015625,"y":-0.288116455078125},{"x":-0.04852294921875,"y":-0.105804443359375},{"x":-0.30682373046875,"y":-0.318359375},{"x":-0.12451171875,"y":-0.1353759765625},{"x":-0.16363525390625,"y":-0.018096923828125},{"x":-0.09381103515625,"y":-0.23480224609375},{"x":-0.12158203125,"y":-0.06146240234375},{"x":0.280517578125,"y":-0.285247802734375},{"x":-0.53424072265625,"y":-0.255859375}],"optimisedCameraToObject":{"translation":{"x":-0.08939954499815218,"y":0.15230058773176838,"z":0.39729187169182056},"rotation":{"quaternion":{"W":0.7021489171553689,"X":0.20066047020872163,"Y":0.1001958969967138,"Z":-0.6757832907509489}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":335.9826965332031,"y":372.4554748535156},{"x":332.4100036621094,"y":337.18988037109375},{"x":330.0588684082031,"y":299.9443359375},{"x":326.2376708984375,"y":260.0234680175781},{"x":322.2530822753906,"y":217.3832550048828},{"x":318.2615966796875,"y":172.0430908203125},{"x":314.62481689453125,"y":122.96778106689453},{"x":377.21844482421875,"y":367.09881591796875},{"x":375.81280517578125,"y":331.6950378417969},{"x":373.80078125,"y":294.58233642578125},{"x":372.09539794921875,"y":255.07870483398438},{"x":369.9466247558594,"y":212.91433715820312},{"x":367.8653564453125,"y":167.47857666015625},{"x":365.73248291015625,"y":118.86949157714844},{"x":418.0681457519531,"y":361.6582336425781},{"x":417.7161560058594,"y":326.4404602050781},{"x":416.8735656738281,"y":289.445068359375},{"x":416.6421813964844,"y":250.00259399414062},{"x":415.95965576171875,"y":208.32423400878906},{"x":415.2171936035156,"y":163.82659912109375},{"x":415.1770324707031,"y":115.66531372070312},{"x":458.3654479980469,"y":356.0220031738281},{"x":459.0064697265625,"y":321.40728759765625},{"x":459.79180908203125,"y":284.9316101074219},{"x":460.8877258300781,"y":245.69288635253906},{"x":461.4212341308594,"y":204.07321166992188},{"x":462.8597717285156,"y":159.6449432373047},{"x":463.7064208984375,"y":111.78621673583984},{"x":497.7293701171875,"y":351.562744140625},{"x":499.3551330566406,"y":316.48651123046875},{"x":501.2765808105469,"y":279.8381652832031},{"x":503.8334045410156,"y":240.9684295654297},{"x":506.1827697753906,"y":200.0029296875},{"x":508.4267883300781,"y":155.20321655273438},{"x":511.70477294921875,"y":108.23625183105469},{"x":536.7310180664062,"y":346.3114318847656},{"x":539.4424438476562,"y":311.7639465332031},{"x":542.9108276367188,"y":275.63922119140625},{"x":546.7367553710938,"y":237.02674865722656},{"x":549.4799194335938,"y":196.046142578125},{"x":553.716064453125,"y":151.28570556640625},{"x":557.9644165039062,"y":104.77891540527344},{"x":574.6658935546875,"y":341.4276428222656},{"x":578.6116943359375,"y":307.0357360839844},{"x":583.0454711914062,"y":270.6964416503906},{"x":587.6207885742188,"y":232.24082946777344},{"x":592.5282592773438,"y":191.55078125},{"x":597.8490600585938,"y":148.14295959472656},{"x":603.9541625976562,"y":100.5843734741211}],"reprojectionErrors":[{"x":-0.399658203125,"y":-0.222686767578125},{"x":0.18438720703125,"y":-0.149322509765625},{"x":-0.64007568359375,"y":-0.312255859375},{"x":-0.200103759765625,"y":-0.237091064453125},{"x":0.176483154296875,"y":-0.13116455078125},{"x":0.30889892578125,"y":-0.3009490966796875},{"x":-0.19219970703125,"y":-0.04076385498046875},{"x":0.015350341796875,"y":-0.33380126953125},{"x":-0.273284912109375,"y":0.04962158203125},{"x":-0.058258056640625,"y":-0.041717529296875},{"x":-0.262664794921875,"y":-0.141326904296875},{"x":-0.1480712890625,"y":-0.2242431640625},{"x":-0.23846435546875,"y":0.0408782958984375},{"x":-0.429779052734375,"y":0.23590087890625},{"x":0.053192138671875,"y":-0.243072509765625},{"x":-0.0423583984375,"y":0.12518310546875},{"x":0.329620361328125,"y":0.119140625},{"x":0.065093994140625,"y":0.198028564453125},{"x":0.22381591796875,"y":-0.08795166015625},{"x":0.41168212890625,"y":-0.4272003173828125},{"x":-0.13690185546875,"y":-0.2864227294921875},{"x":-0.09442138671875,"y":0.157470703125},{"x":0.01837158203125,"y":0.09234619140625},{"x":0.0390625,"y":-0.232666015625},{"x":-0.19354248046875,"y":-0.1207122802734375},{"x":0.199249267578125,"y":-0.1864471435546875},{"x":-0.24346923828125,"y":-0.2667999267578125},{"x":-0.01739501953125,"y":-0.04235076904296875},{"x":-0.022186279296875,"y":-0.508514404296875},{"x":0.263946533203125,"y":0.056427001953125},{"x":0.377838134765625,"y":0.102874755859375},{"x":-0.008392333984375,"y":0.079833984375},{"x":-0.03857421875,"y":-0.3651123046875},{"x":0.200408935546875,"y":0.24884033203125},{"x":-0.413421630859375,"y":-0.03939056396484375},{"x":-0.2779541015625,"y":-0.27545166015625},{"x":0.03936767578125,"y":-0.07196044921875},{"x":-0.20953369140625,"y":-0.352264404296875},{"x":-0.6070556640625,"y":-0.40142822265625},{"x":0.3074951171875,"y":-0.56024169921875},{"x":-0.01837158203125,"y":0.3319854736328125},{"x":-0.07745361328125,"y":-0.044342041015625},{"x":-0.1348876953125,"y":-0.3062744140625},{"x":0.0255126953125,"y":-0.092376708984375},{"x":-0.04754638671875,"y":0.03680419921875},{"x":0.0162353515625,"y":0.0590972900390625},{"x":0.0533447265625,"y":-0.123138427734375},{"x":0.01318359375,"y":-0.2711944580078125},{"x":-0.4404296875,"y":0.7694931030273438}],"optimisedCameraToObject":{"translation":{"x":-0.06332270001311688,"y":0.08153530536102126,"z":0.42002700042068847},"rotation":{"quaternion":{"W":0.657672552786059,"X":0.23670593169498372,"Y":0.11334805013756705,"Z":-0.7061085856596631}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":149.86721801757812,"y":330.894287109375},{"x":150.78646850585938,"y":294.9491882324219},{"x":151.890625,"y":257.7227783203125},{"x":153.1271209716797,"y":218.0967559814453},{"x":154.2246551513672,"y":176.2801971435547},{"x":155.29034423828125,"y":132.23536682128906},{"x":156.38751220703125,"y":85.59054565429688},{"x":191.35177612304688,"y":335.7319641113281},{"x":193.87574768066406,"y":300.720947265625},{"x":195.779052734375,"y":263.5686950683594},{"x":198.1315460205078,"y":224.4159393310547},{"x":200.65264892578125,"y":183.61532592773438},{"x":202.88645935058594,"y":139.88290405273438},{"x":205.1992645263672,"y":94.01908874511719},{"x":232.2598114013672,"y":340.41168212890625},{"x":235.35911560058594,"y":305.69305419921875},{"x":238.77825927734375,"y":269.5202941894531},{"x":242.11767578125,"y":230.75189208984375},{"x":245.47860717773438,"y":190.45431518554688},{"x":248.78370666503906,"y":147.44088745117188},{"x":253.04409790039062,"y":102.67726135253906},{"x":272.3867492675781,"y":345.5143737792969},{"x":276.3677673339844,"y":310.85223388671875},{"x":280.9718017578125,"y":275.08740234375},{"x":285.2265930175781,"y":237.00621032714844},{"x":290.03436279296875,"y":197.04661560058594},{"x":294.5375671386719,"y":154.50515747070312},{"x":299.6953430175781,"y":110.1443099975586},{"x":311.6781311035156,"y":349.90863037109375},{"x":316.98150634765625,"y":316.1786804199219},{"x":322.0094909667969,"y":280.5862121582031},{"x":327.4378662109375,"y":243.09315490722656},{"x":333.0807800292969,"y":203.6486358642578},{"x":339.06988525390625,"y":161.95391845703125},{"x":345.6327209472656,"y":118.2198715209961},{"x":350.8694152832031,"y":355.3047180175781},{"x":356.5166320800781,"y":321.4974365234375},{"x":362.97418212890625,"y":286.1893310546875},{"x":369.1387634277344,"y":249.1246795654297},{"x":376.0498962402344,"y":210.1953582763672},{"x":383.0219421386719,"y":169.1532440185547},{"x":390.8370056152344,"y":125.54827117919922},{"x":388.727294921875,"y":359.8094482421875},{"x":395.2314453125,"y":326.39202880859375},{"x":402.6241455078125,"y":291.7785949707031},{"x":409.9408264160156,"y":254.9832000732422},{"x":417.6612548828125,"y":216.09031677246094},{"x":425.7584533691406,"y":175.77430725097656},{"x":434.65826416015625,"y":133.0370330810547}],"reprojectionErrors":[{"x":0.32257080078125,"y":-0.436309814453125},{"x":0.41021728515625,"y":-0.021484375},{"x":0.3597412109375,"y":-0.175537109375},{"x":0.2275543212890625,"y":0.067169189453125},{"x":0.2892913818359375,"y":0.327667236328125},{"x":0.442626953125,"y":0.45404052734375},{"x":0.629608154296875,"y":0.6055831909179688},{"x":0.136932373046875,"y":-0.261322021484375},{"x":-0.3433074951171875,"y":-0.3746337890625},{"x":-0.1014251708984375,"y":-0.16070556640625},{"x":-0.1989593505859375,"y":0.0912017822265625},{"x":-0.3460845947265625,"y":-0.1366119384765625},{"x":-0.0765838623046875,"y":0.25567626953125},{"x":0.2547607421875,"y":0.26161956787109375},{"x":-0.1049041748046875,"y":0.010040283203125},{"x":-0.1555938720703125,"y":0.001129150390625},{"x":-0.37249755859375,"y":-0.332672119140625},{"x":-0.3435821533203125,"y":0.005767822265625},{"x":-0.156219482421875,"y":-0.210540771484375},{"x":0.2823944091796875,"y":0.0262603759765625},{"x":-0.0216217041015625,"y":-0.44934844970703125},{"x":-0.179656982421875,"y":-0.201171875},{"x":-0.13775634765625,"y":0.12127685546875},{"x":-0.515533447265625,"y":-0.1986083984375},{"x":-0.32427978515625,"y":-0.087738037109375},{"x":-0.44805908203125,"y":-0.1401214599609375},{"x":-0.009063720703125,"y":0.1739959716796875},{"x":0.056182861328125,"y":-0.1019134521484375},{"x":-0.014739990234375,"y":0.23822021484375},{"x":-0.350311279296875,"y":0.007781982421875},{"x":-0.15960693359375,"y":-0.072265625},{"x":-0.098388671875,"y":-0.1006927490234375},{"x":0.041473388671875,"y":-0.1783905029296875},{"x":0.15301513671875,"y":-0.1754913330078125},{"x":0.03631591796875,"y":-0.4912567138671875},{"x":-0.328277587890625,"y":-0.380157470703125},{"x":-0.090911865234375,"y":-0.162322998046875},{"x":-0.367706298828125,"y":-0.123870849609375},{"x":-0.031829833984375,"y":-0.1422882080078125},{"x":-0.096771240234375,"y":-0.257171630859375},{"x":0.152008056640625,"y":-0.3845672607421875},{"x":-0.035308837890625,"y":-0.2574310302734375},{"x":0.12982177734375,"y":-0.161468505859375},{"x":0.39996337890625,"y":0.0294189453125},{"x":0.121063232421875,"y":-0.232879638671875},{"x":0.28436279296875,"y":-0.092254638671875},{"x":0.439727783203125,"y":0.22308349609375},{"x":0.646942138671875,"y":-0.120880126953125},{"x":0.516815185546875,"y":-0.303863525390625}],"optimisedCameraToObject":{"translation":{"x":-0.1866986210437024,"y":0.05189505703963445,"z":0.4371469864300427},"rotation":{"quaternion":{"W":0.7435262808793736,"X":0.19052750488269202,"Y":0.12231856899029324,"Z":-0.6292107017565972}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":260.69403076171875,"y":515.963623046875},{"x":246.1876678466797,"y":448.4525451660156},{"x":232.0056610107422,"y":382.94122314453125},{"x":217.63636779785156,"y":318.9758605957031},{"x":203.71630859375,"y":255.99476623535156},{"x":189.64547729492188,"y":194.19383239746094},{"x":175.93414306640625,"y":133.03176879882812},{"x":327.16094970703125,"y":496.60723876953125},{"x":312.05517578125,"y":430.6054992675781},{"x":297.4358825683594,"y":366.7966003417969},{"x":282.98388671875,"y":303.9602355957031},{"x":268.27691650390625,"y":243.36691284179688},{"x":254.40171813964844,"y":181.8313751220703},{"x":240.6330108642578,"y":122.47248840332031},{"x":390.38006591796875,"y":478.0368347167969},{"x":374.8199768066406,"y":413.76409912109375},{"x":360.1762390136719,"y":351.20892333984375},{"x":344.8379211425781,"y":289.7818908691406},{"x":330.3945617675781,"y":229.5931396484375},{"x":316.079833984375,"y":169.9771728515625},{"x":302.01904296875,"y":112.25658416748047},{"x":451.3851318359375,"y":460.4209289550781},{"x":435.4379577636719,"y":397.32171630859375},{"x":420.30340576171875,"y":336.4232177734375},{"x":404.9696044921875,"y":276.125732421875},{"x":390.21624755859375,"y":217.73744201660156},{"x":375.7232666015625,"y":159.1183624267578},{"x":361.2433166503906,"y":102.4006576538086},{"x":509.92108154296875,"y":443.3703918457031},{"x":493.7966613769531,"y":382.114013671875},{"x":477.9704284667969,"y":322.0621643066406},{"x":462.78558349609375,"y":263.1185302734375},{"x":447.1580810546875,"y":205.30685424804688},{"x":432.71490478515625,"y":148.29034423828125},{"x":418.32794189453125,"y":92.4276351928711},{"x":566.785400390625,"y":427.1936950683594},{"x":550.009521484375,"y":366.7912902832031},{"x":534.1528930664062,"y":308.2074279785156},{"x":518.7182006835938,"y":250.3951416015625},{"x":503.2882080078125,"y":194.16177368164062},{"x":488.3013916015625,"y":137.80361938476562},{"x":473.5104064941406,"y":83.41233825683594},{"x":620.8378295898438,"y":411.41949462890625},{"x":604.5110473632812,"y":352.68853759765625},{"x":588.072509765625,"y":294.95831298828125},{"x":572.3175659179688,"y":238.25439453125},{"x":556.3950805664062,"y":182.4742889404297},{"x":541.5023803710938,"y":127.47271728515625},{"x":526.5505981445312,"y":73.7701416015625}],"reprojectionErrors":[{"x":0.451385498046875,"y":-0.39630126953125},{"x":0.1784515380859375,"y":0.210968017578125},{"x":-0.122772216796875,"y":0.168212890625},{"x":0.0483856201171875,"y":-0.120452880859375},{"x":0.0449981689453125,"y":-0.1408843994140625},{"x":0.457122802734375,"y":-0.1341552734375},{"x":0.7649993896484375,"y":0.3978118896484375},{"x":-0.09576416015625,"y":-0.18994140625},{"x":-0.13189697265625,"y":0.437713623046875},{"x":-0.35400390625,"y":0.164581298828125},{"x":-0.453857421875,"y":0.164031982421875},{"x":-0.01953125,"y":-0.8792266845703125},{"x":-0.1477508544921875,"y":0.1774139404296875},{"x":-0.1226959228515625,"y":0.17425537109375},{"x":8.85009765625E-4,"y":-0.00469970703125},{"x":0.095184326171875,"y":0.35211181640625},{"x":-0.422943115234375,"y":0.229339599609375},{"x":0.0465087890625,"y":0.17218017578125},{"x":-0.09625244140625,"y":0.0282135009765625},{"x":-0.094818115234375,"y":0.422576904296875},{"x":-0.083953857421875,"y":-0.0059051513671875},{"x":-0.128936767578125,"y":-0.057037353515625},{"x":0.06341552734375,"y":0.517608642578125},{"x":-0.25042724609375,"y":0.07891845703125},{"x":-0.069366455078125,"y":0.184783935546875},{"x":-0.183319091796875,"y":-0.5129241943359375},{"x":-0.28204345703125,"y":0.08758544921875},{"x":-0.127593994140625,"y":-0.18241119384765625},{"x":-0.079986572265625,"y":-0.001861572265625},{"x":0.032012939453125,"y":0.058929443359375},{"x":0.15399169921875,"y":0.05511474609375},{"x":-0.06787109375,"y":0.04345703125},{"x":0.440338134765625,"y":-0.037628173828125},{"x":0.041900634765625,"y":0.1124725341796875},{"x":-0.144378662109375,"y":0.10045623779296875},{"x":-0.51165771484375,"y":-0.188232421875},{"x":0.0225830078125,"y":0.289276123046875},{"x":-0.05316162109375,"y":0.0435791015625},{"x":-0.2520751953125,"y":0.0842132568359375},{"x":-0.16693115234375,"y":-0.432098388671875},{"x":-0.245819091796875,"y":0.1640777587890625},{"x":-0.2506103515625,"y":-0.251861572265625},{"x":-0.15625,"y":-0.182159423828125},{"x":-0.2747802734375,"y":-0.160003662109375},{"x":0.0283203125,"y":-0.085174560546875},{"x":-0.05267333984375,"y":-0.018707275390625},{"x":0.3233642578125,"y":0.1077423095703125},{"x":-0.05023193359375,"y":0.4069061279296875},{"x":-0.09381103515625,"y":0.32701873779296875}],"optimisedCameraToObject":{"translation":{"x":-0.07039215144047704,"y":0.11919007948410354,"z":0.2491374458704275},"rotation":{"quaternion":{"W":0.6151303102187313,"X":0.02387901083940901,"Y":-0.11415712188645476,"Z":-0.7797516564997731}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":416.5469970703125,"y":518.23876953125},{"x":396.3773498535156,"y":459.06341552734375},{"x":376.0103759765625,"y":398.90435791015625},{"x":354.87310791015625,"y":337.0115966796875},{"x":333.3517761230469,"y":273.9483947753906},{"x":310.94964599609375,"y":208.7898712158203},{"x":288.1636962890625,"y":141.85440063476562},{"x":456.380859375,"y":484.49932861328125},{"x":437.7421569824219,"y":428.7563171386719},{"x":418.9906005859375,"y":371.8916015625},{"x":399.8716735839844,"y":313.5655517578125},{"x":380.1560974121094,"y":254.09564208984375},{"x":359.95751953125,"y":192.8825225830078},{"x":339.1092529296875,"y":130.22567749023438},{"x":491.5133361816406,"y":454.6941833496094},{"x":474.20294189453125,"y":401.9616394042969},{"x":456.8701171875,"y":348.1448669433594},{"x":439.0196533203125,"y":293.1131591796875},{"x":421.4383850097656,"y":236.92025756835938},{"x":402.737060546875,"y":179.06585693359375},{"x":383.9435729980469,"y":119.94778442382812},{"x":523.0077514648438,"y":428.24652099609375},{"x":507.0431823730469,"y":377.9974060058594},{"x":490.8846740722656,"y":327.0618896484375},{"x":474.4557800292969,"y":274.7996826171875},{"x":457.93597412109375,"y":221.3756103515625},{"x":441.19842529296875,"y":166.71829223632812},{"x":423.6672058105469,"y":110.9306411743164},{"x":551.0842895507812,"y":404.8179626464844},{"x":536.3008422851562,"y":356.75457763671875},{"x":521.3323364257812,"y":308.0321960449219},{"x":506.1437683105469,"y":258.26031494140625},{"x":491.0164489746094,"y":207.63568115234375},{"x":475.14678955078125,"y":155.50291442871094},{"x":459.20355224609375,"y":102.54316711425781},{"x":576.7890625,"y":383.2203674316406},{"x":562.8313598632812,"y":337.429443359375},{"x":548.99462890625,"y":290.9260559082031},{"x":534.9035034179688,"y":243.505615234375},{"x":520.5535278320312,"y":195.11911010742188},{"x":505.80548095703125,"y":145.30018615722656},{"x":491.12451171875,"y":95.07804107666016},{"x":599.9476318359375,"y":363.8676452636719},{"x":587.0123901367188,"y":319.8540954589844},{"x":573.998779296875,"y":275.359130859375},{"x":560.6796264648438,"y":229.96803283691406},{"x":547.188232421875,"y":183.82994079589844},{"x":533.8145141601562,"y":136.34791564941406},{"x":519.8649291992188,"y":88.23795318603516}],"reprojectionErrors":[{"x":-0.349822998046875,"y":-0.3572998046875},{"x":-0.2406005859375,"y":0.12603759765625},{"x":-0.42340087890625,"y":0.095977783203125},{"x":-0.346588134765625,"y":0.237640380859375},{"x":-0.4189453125,"y":-0.0809326171875},{"x":-0.1676025390625,"y":-0.007568359375},{"x":-0.1148681640625,"y":0.0622711181640625},{"x":-0.523406982421875,"y":-0.06268310546875},{"x":-0.25701904296875,"y":0.15887451171875},{"x":-0.295135498046875,"y":0.172088623046875},{"x":-0.40045166015625,"y":0.262176513671875},{"x":-0.361785888671875,"y":0.0542449951171875},{"x":-0.311920166015625,"y":0.0870513916015625},{"x":-0.104339599609375,"y":-0.0028839111328125},{"x":-0.457550048828125,"y":0.08966064453125},{"x":-0.075286865234375,"y":0.148101806640625},{"x":-0.02996826171875,"y":0.10113525390625},{"x":0.1595458984375,"y":0.033416748046875},{"x":-0.308319091796875,"y":-0.1573944091796875},{"x":-0.05987548828125,"y":-0.02197265625},{"x":-0.13934326171875,"y":-0.01194000244140625},{"x":-0.49407958984375,"y":0.06341552734375},{"x":-0.209930419921875,"y":0.2088623046875},{"x":-0.043914794921875,"y":-0.0296630859375},{"x":0.06878662109375,"y":-0.05133056640625},{"x":-0.063507080078125,"y":-0.0624237060546875},{"x":-0.326690673828125,"y":-0.0349578857421875},{"x":-0.158294677734375,"y":-0.11751556396484375},{"x":-0.27923583984375,"y":-0.290802001953125},{"x":-0.0888671875,"y":5.79833984375E-4},{"x":0.0135498046875,"y":-0.017364501953125},{"x":0.05328369140625,"y":0.011810302734375},{"x":-0.261138916015625,"y":-0.1443328857421875},{"x":-0.13677978515625,"y":0.1323394775390625},{"x":-0.2535400390625,"y":0.12152099609375},{"x":-0.39697265625,"y":-0.177642822265625},{"x":-0.0772705078125,"y":-0.03436279296875},{"x":-0.11907958984375,"y":-0.0589599609375},{"x":-0.1551513671875,"y":-0.0764007568359375},{"x":-0.1895751953125,"y":-0.068634033203125},{"x":-0.092132568359375,"y":0.3984222412109375},{"x":-0.337249755859375,"y":0.261749267578125},{"x":-0.2962646484375,"y":-0.3309326171875},{"x":-0.1544189453125,"y":-0.02178955078125},{"x":-0.14727783203125,"y":-0.03509521484375},{"x":-0.05462646484375,"y":0.017974853515625},{"x":-0.01708984375,"y":-0.03875732421875},{"x":-0.33209228515625,"y":0.363494873046875},{"x":-0.31402587890625,"y":0.47930145263671875}],"optimisedCameraToObject":{"translation":{"x":-0.002846783474987113,"y":0.125887956527986,"z":0.2545717560597775},"rotation":{"quaternion":{"W":0.5254908744967247,"X":0.2638065842249298,"Y":-0.2589158652394213,"Z":-0.7663080331482662}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":318.0772399902344,"y":540.03564453125},{"x":304.4088439941406,"y":476.0615539550781},{"x":291.06201171875,"y":418.6055603027344},{"x":279.1396789550781,"y":364.6170654296875},{"x":267.92352294921875,"y":315.0318298339844},{"x":257.5175476074219,"y":268.4412841796875},{"x":247.8678741455078,"y":225.19961547851562},{"x":380.6106262207031,"y":521.0836181640625},{"x":364.5364685058594,"y":459.68048095703125},{"x":349.1800231933594,"y":403.2077331542969},{"x":335.1354675292969,"y":350.9098205566406},{"x":322.12139892578125,"y":302.21929931640625},{"x":309.8099365234375,"y":256.8783874511719},{"x":298.6763916015625,"y":214.9141082763672},{"x":440.2630310058594,"y":503.2288818359375},{"x":421.77435302734375,"y":443.3047790527344},{"x":404.37078857421875,"y":388.20574951171875},{"x":388.94866943359375,"y":337.1391296386719},{"x":374.1770935058594,"y":290.007568359375},{"x":360.42047119140625,"y":245.8341064453125},{"x":347.59735107421875,"y":204.14883422851562},{"x":498.7082214355469,"y":485.767822265625},{"x":477.9056091308594,"y":427.3115234375},{"x":459.1396179199219,"y":373.93597412109375},{"x":441.46734619140625,"y":324.00225830078125},{"x":425.232666015625,"y":277.8291015625},{"x":409.91485595703125,"y":234.2943878173828},{"x":395.8304138183594,"y":193.91661071777344},{"x":554.8916015625,"y":469.091064453125},{"x":532.3231201171875,"y":412.1479187011719},{"x":511.4583740234375,"y":359.93310546875},{"x":492.3544616699219,"y":311.0975646972656},{"x":474.6657409667969,"y":265.9742736816406},{"x":457.981201171875,"y":223.85336303710938},{"x":442.44012451171875,"y":183.9359130859375},{"x":609.8898315429688,"y":452.8299560546875},{"x":585.3655395507812,"y":397.2122497558594},{"x":563.2174072265625,"y":346.4174499511719},{"x":542.4961547851562,"y":298.81134033203125},{"x":523.3419189453125,"y":254.69586181640625},{"x":505.0900573730469,"y":212.85888671875},{"x":488.160400390625,"y":174.07586669921875},{"x":662.8329467773438,"y":436.9070739746094},{"x":636.9415283203125,"y":382.9956970214844},{"x":612.760498046875,"y":333.0326232910156},{"x":590.666015625,"y":286.44915771484375},{"x":570.101318359375,"y":243.2345733642578},{"x":551.0316162109375,"y":202.70574951171875},{"x":532.6757202148438,"y":164.26893615722656}],"reprojectionErrors":[{"x":0.244110107421875,"y":-0.3775634765625},{"x":-0.198486328125,"y":0.648345947265625},{"x":0.13507080078125,"y":0.05645751953125},{"x":0.016845703125,"y":0.3394775390625},{"x":0.058502197265625,"y":0.0853271484375},{"x":0.06439208984375,"y":0.29345703125},{"x":0.0092010498046875,"y":0.25628662109375},{"x":-0.284088134765625,"y":0.02484130859375},{"x":-0.57550048828125,"y":0.210968017578125},{"x":-0.32806396484375,"y":0.1593017578125},{"x":-0.2769775390625,"y":0.09881591796875},{"x":-0.261505126953125,"y":0.1463623046875},{"x":-0.0576171875,"y":0.1717529296875},{"x":-0.230560302734375,"y":-0.1877899169921875},{"x":0.07379150390625,"y":-0.080352783203125},{"x":0.089630126953125,"y":0.27783203125},{"x":0.419830322265625,"y":0.308349609375},{"x":0.013275146484375,"y":0.306304931640625},{"x":0.06805419921875,"y":-0.057708740234375},{"x":0.105224609375,"y":-0.1748809814453125},{"x":0.106842041015625,"y":0.105377197265625},{"x":-0.251373291015625,"y":-0.02056884765625},{"x":0.1072998046875,"y":0.445953369140625},{"x":-0.04254150390625,"y":0.1455078125},{"x":0.0753173828125,"y":0.246368408203125},{"x":-0.026275634765625,"y":0.02520751953125},{"x":0.049468994140625,"y":0.2544403076171875},{"x":-0.121551513671875,"y":0.111724853515625},{"x":-0.10736083984375,"y":-0.215301513671875},{"x":0.172119140625,"y":0.2440185546875},{"x":0.391632080078125,"y":0.115753173828125},{"x":0.317291259765625,"y":0.30340576171875},{"x":0.142303466796875,"y":0.090087890625},{"x":0.145721435546875,"y":-0.1468353271484375},{"x":0.073333740234375,"y":0.102142333984375},{"x":-0.47979736328125,"y":-0.32281494140625},{"x":0.02716064453125,"y":0.2510986328125},{"x":-0.09423828125,"y":-0.020263671875},{"x":-0.0802001953125,"y":0.075042724609375},{"x":-0.23114013671875,"y":-0.1295623779296875},{"x":-0.021331787109375,"y":0.2617034912109375},{"x":0.008087158203125,"y":0.1974639892578125},{"x":-0.413818359375,"y":-0.29083251953125},{"x":-0.15966796875,"y":-0.045135498046875},{"x":0.22528076171875,"y":0.075958251953125},{"x":0.17205810546875,"y":0.240509033203125},{"x":0.07049560546875,"y":0.112640380859375},{"x":-0.18963623046875,"y":0.0742034912109375},{"x":0.046142578125,"y":0.4557342529296875}],"optimisedCameraToObject":{"translation":{"x":-0.049510211124482104,"y":0.13032330788324134,"z":0.25385687289299},"rotation":{"quaternion":{"W":0.584825321654978,"X":-0.12972652701125964,"Y":-0.2120331118389241,"Z":-0.7721349175012425}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":307.17657470703125,"y":500.3337707519531},{"x":294.00390625,"y":441.13037109375},{"x":283.1438903808594,"y":386.26202392578125},{"x":272.2541198730469,"y":336.4093017578125},{"x":262.7958984375,"y":290.5818176269531},{"x":253.80142211914062,"y":247.69607543945312},{"x":368.92901611328125,"y":483.6756286621094},{"x":353.6610412597656,"y":425.87042236328125},{"x":339.87933349609375,"y":372.8079833984375},{"x":327.1522216796875,"y":324.42352294921875},{"x":315.3954162597656,"y":279.10650634765625},{"x":304.518310546875,"y":237.34771728515625},{"x":446.6108703613281,"y":529.2217407226562},{"x":427.6329040527344,"y":467.40765380859375},{"x":410.3550720214844,"y":411.25860595703125},{"x":394.54803466796875,"y":359.04083251953125},{"x":379.83331298828125,"y":312.1299133300781},{"x":366.223876953125,"y":268.0414123535156},{"x":353.8587646484375,"y":227.6125946044922},{"x":506.6834716796875,"y":511.7632751464844},{"x":485.2646789550781,"y":451.6229553222656},{"x":465.87384033203125,"y":396.87103271484375},{"x":447.8388366699219,"y":346.74737548828125},{"x":431.49639892578125,"y":300.48291015625},{"x":416.1639404296875,"y":257.543701171875},{"x":401.9381408691406,"y":217.92234802246094},{"x":564.5591430664062,"y":494.6625671386719},{"x":540.7218627929688,"y":436.2884521484375},{"x":519.0390014648438,"y":383.2307434082031},{"x":499.29986572265625,"y":334.19268798828125},{"x":481.0068054199219,"y":289.0885009765625},{"x":464.0124206542969,"y":247.0472412109375},{"x":448.43975830078125,"y":208.3365936279297},{"x":620.84814453125,"y":478.48956298828125},{"x":594.9700927734375,"y":421.46929931640625},{"x":571.551025390625,"y":369.9625244140625},{"x":549.8160400390625,"y":322.0380554199219},{"x":529.895751953125,"y":277.931396484375},{"x":511.3050537109375,"y":236.896728515625},{"x":494.1851501464844,"y":199.1476287841797},{"x":675.1011962890625,"y":462.86956787109375},{"x":647.253662109375,"y":407.4452819824219},{"x":621.8485107421875,"y":356.91497802734375},{"x":598.3814086914062,"y":310.03948974609375},{"x":576.9771728515625,"y":267.13067626953125},{"x":557.1944580078125,"y":227.12680053710938},{"x":538.7382202148438,"y":189.8633270263672}],"reprojectionErrors":[{"x":-0.2022705078125,"y":0.3428955078125},{"x":0.4324951171875,"y":0.006439208984375},{"x":-0.179931640625,"y":0.39678955078125},{"x":0.171051025390625,"y":0.207427978515625},{"x":-0.08673095703125,"y":-0.098114013671875},{"x":-0.0794677734375,"y":0.1170501708984375},{"x":-0.533660888671875,"y":0.189117431640625},{"x":-0.291595458984375,"y":0.148040771484375},{"x":-0.27593994140625,"y":0.20550537109375},{"x":-0.208526611328125,"y":-0.163665771484375},{"x":-0.1346435546875,"y":0.153289794921875},{"x":-0.073760986328125,"y":0.242462158203125},{"x":0.1658935546875,"y":-0.0963134765625},{"x":0.155303955078125,"y":0.188232421875},{"x":0.084503173828125,"y":0.10467529296875},{"x":-0.02239990234375,"y":0.724151611328125},{"x":0.04083251953125,"y":0.1143798828125},{"x":0.11541748046875,"y":0.288970947265625},{"x":-0.0618896484375,"y":0.009552001953125},{"x":-0.08782958984375,"y":-0.1646728515625},{"x":-0.003662109375,"y":0.2181396484375},{"x":-0.131591796875,"y":0.276458740234375},{"x":-0.02337646484375,"y":0.146209716796875},{"x":-0.204254150390625,"y":0.070770263671875},{"x":-0.151458740234375,"y":0.13818359375},{"x":-0.098175048828125,"y":-0.0247650146484375},{"x":-0.1239013671875,"y":-0.01934814453125},{"x":0.19256591796875,"y":0.284912109375},{"x":0.32757568359375,"y":0.118072509765625},{"x":0.252288818359375,"y":0.188262939453125},{"x":0.26190185546875,"y":0.084136962890625},{"x":0.33172607421875,"y":0.254180908203125},{"x":0.1915283203125,"y":0.069091796875},{"x":-0.44635009765625,"y":-0.260986328125},{"x":-0.12799072265625,"y":0.29827880859375},{"x":-0.15509033203125,"y":-0.0159912109375},{"x":-0.0059814453125,"y":0.171722412109375},{"x":-0.025390625,"y":0.15545654296875},{"x":0.089141845703125,"y":0.280181884765625},{"x":0.0399169921875,"y":-0.0113525390625},{"x":-0.50714111328125,"y":-0.54345703125},{"x":-0.12200927734375,"y":-0.045074462890625},{"x":0.0595703125,"y":0.0062255859375},{"x":0.27752685546875,"y":0.324432373046875},{"x":0.18267822265625,"y":0.15203857421875},{"x":0.02471923828125,"y":0.170196533203125},{"x":-0.0657958984375,"y":0.2164306640625}],"optimisedCameraToObject":{"translation":{"x":-0.04777961806190264,"y":0.13598084141105451,"z":0.24367581716410797},"rotation":{"quaternion":{"W":0.5829375375558049,"X":-0.14974951296718148,"Y":-0.23436818587210034,"Z":-0.7634333396737971}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img11.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":400.06549072265625,"y":445.9293518066406},{"x":382.9204406738281,"y":423.89654541015625},{"x":364.7845764160156,"y":400.6599426269531},{"x":345.2159729003906,"y":375.8628234863281},{"x":324.64776611328125,"y":349.1144714355469},{"x":302.2231750488281,"y":320.79315185546875},{"x":278.4147033691406,"y":290.2289733886719},{"x":427.91632080078125,"y":420.8387756347656},{"x":411.75225830078125,"y":398.20965576171875},{"x":394.7666015625,"y":374.26068115234375},{"x":376.435302734375,"y":349.0074462890625},{"x":357.0357360839844,"y":321.9803771972656},{"x":336.185791015625,"y":292.9826965332031},{"x":313.91595458984375,"y":261.8892517089844},{"x":455.04803466796875,"y":396.4869689941406},{"x":439.8075256347656,"y":373.4039611816406},{"x":423.8321533203125,"y":348.9942932128906},{"x":406.7684326171875,"y":323.17364501953125},{"x":388.68182373046875,"y":295.60345458984375},{"x":369.0622863769531,"y":265.9937744140625},{"x":348.4420471191406,"y":234.32254028320312},{"x":481.7522277832031,"y":372.5276184082031},{"x":467.3509826660156,"y":348.9601135253906},{"x":452.4822998046875,"y":324.16510009765625},{"x":436.4610900878906,"y":297.821533203125},{"x":419.6944580078125,"y":269.79693603515625},{"x":401.3395690917969,"y":239.61891174316406},{"x":382.00201416015625,"y":207.3668212890625},{"x":507.7852783203125,"y":349.1766357421875},{"x":494.3333740234375,"y":325.27935791015625},{"x":480.2723388671875,"y":299.9507751464844},{"x":465.5085754394531,"y":273.0280456542969},{"x":449.7333068847656,"y":244.64376831054688},{"x":432.845703125,"y":213.84762573242188},{"x":414.8404235839844,"y":181.0865020751953},{"x":533.4261474609375,"y":326.1344909667969},{"x":520.9425659179688,"y":302.00701904296875},{"x":508.0303039550781,"y":276.08197021484375},{"x":494.1401672363281,"y":248.7632293701172},{"x":479.32257080078125,"y":219.811767578125},{"x":463.7994384765625,"y":188.59051513671875},{"x":447.03302001953125,"y":155.30694580078125},{"x":558.7716674804688,"y":303.72308349609375},{"x":546.9908447265625,"y":279.0557861328125},{"x":534.9400024414062,"y":252.94271850585938},{"x":521.905517578125,"y":225.18331909179688},{"x":508.1968688964844,"y":195.84445190429688},{"x":493.7278137207031,"y":164.0002899169922},{"x":478.1692810058594,"y":130.3396759033203}],"reprojectionErrors":[{"x":-0.14251708984375,"y":-0.306243896484375},{"x":-0.124603271484375,"y":-0.182403564453125},{"x":-0.20135498046875,"y":-0.245147705078125},{"x":-0.039825439453125,"y":-0.27734375},{"x":-0.1971435546875,"y":-0.047119140625},{"x":0.041595458984375,"y":-0.11444091796875},{"x":0.040985107421875,"y":-0.018096923828125},{"x":-0.23455810546875,"y":-0.136322021484375},{"x":-0.161651611328125,"y":0.05816650390625},{"x":-0.2742919921875,"y":0.163818359375},{"x":-0.14837646484375,"y":0.025299072265625},{"x":-0.1749267578125,"y":-0.0467529296875},{"x":-0.101470947265625,"y":-0.0369873046875},{"x":-0.1072998046875,"y":-0.028289794921875},{"x":-0.171417236328125,"y":-0.1739501953125},{"x":-0.025909423828125,"y":-0.02459716796875},{"x":-0.078582763671875,"y":0.026519775390625},{"x":-0.067535400390625,"y":-0.076141357421875},{"x":-0.16217041015625,"y":-0.152679443359375},{"x":0.029083251953125,"y":-0.094085693359375},{"x":-0.16162109375,"y":-0.0854644775390625},{"x":-0.224884033203125,"y":-0.0914306640625},{"x":0.03973388671875,"y":0.068634033203125},{"x":-0.09124755859375,"y":0.016876220703125},{"x":-0.01641845703125,"y":-0.06524658203125},{"x":-0.23785400390625,"y":-0.20361328125},{"x":-0.020751953125,"y":-0.105987548828125},{"x":-0.094268798828125,"y":-0.0577850341796875},{"x":-0.132293701171875,"y":-0.122406005859375},{"x":0.10528564453125,"y":-0.082550048828125},{"x":0.15533447265625,"y":-0.063323974609375},{"x":0.034942626953125,"y":-0.041229248046875},{"x":-0.03363037109375,"y":-0.306610107421875},{"x":-0.0479736328125,"y":-0.0884246826171875},{"x":-0.115081787109375,"y":-0.038238525390625},{"x":-0.15460205078125,"y":0.01568603515625},{"x":0.00274658203125,"y":-0.14166259765625},{"x":-0.1451416015625,"y":0.03558349609375},{"x":-0.11871337890625,"y":0.004638671875},{"x":-0.047149658203125,"y":-0.152435302734375},{"x":-0.2418212890625,"y":0.023162841796875},{"x":-0.266876220703125,"y":0.1208038330078125},{"x":-0.3712158203125,"y":-0.015228271484375},{"x":-0.061279296875,"y":-0.038818359375},{"x":-0.1556396484375,"y":-0.08917236328125},{"x":-0.004150390625,"y":-0.104034423828125},{"x":0.01226806640625,"y":-0.3064422607421875},{"x":-0.10125732421875,"y":0.05242919921875},{"x":-0.10797119140625,"y":0.0822296142578125}],"optimisedCameraToObject":{"translation":{"x":-0.00804972634912372,"y":0.1479023099334526,"z":0.47523203000507486},"rotation":{"quaternion":{"W":0.4294705498966302,"X":0.30491432112147887,"Y":0.03994732271908964,"Z":-0.849109247949927}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img12.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":338.3634033203125,"y":368.2750244140625},{"x":331.09423828125,"y":341.3652648925781},{"x":323.52508544921875,"y":312.9315185546875},{"x":314.97735595703125,"y":282.3391418457031},{"x":306.0550537109375,"y":249.2495880126953},{"x":295.99847412109375,"y":213.1549072265625},{"x":285.2341003417969,"y":174.72811889648438},{"x":373.2569580078125,"y":356.29339599609375},{"x":367.45306396484375,"y":329.64483642578125},{"x":360.9817199707031,"y":300.8885803222656},{"x":354.30548095703125,"y":269.6953430175781},{"x":346.93084716796875,"y":236.85572814941406},{"x":338.9945373535156,"y":200.92803955078125},{"x":330.0884704589844,"y":162.13047790527344},{"x":407.686279296875,"y":344.9640197753906},{"x":402.90264892578125,"y":317.79791259765625},{"x":397.6742858886719,"y":288.9435119628906},{"x":392.2249450683594,"y":258.0914611816406},{"x":386.1871643066406,"y":224.75851440429688},{"x":380.0088195800781,"y":188.5705108642578},{"x":373.1387023925781,"y":149.9840087890625},{"x":441.5454406738281,"y":333.43707275390625},{"x":437.9104919433594,"y":306.0917053222656},{"x":433.9208984375,"y":277.0910949707031},{"x":429.942626953125,"y":246.1292266845703},{"x":425.3064880371094,"y":212.91555786132812},{"x":421.1845703125,"y":176.81214904785156},{"x":415.6334228515625,"y":138.07217407226562},{"x":474.2669677734375,"y":322.0856018066406},{"x":471.6901550292969,"y":294.9560852050781},{"x":469.1703186035156,"y":265.86761474609375},{"x":466.2121276855469,"y":234.5196533203125},{"x":463.7511901855469,"y":201.32925415039062},{"x":460.44189453125,"y":164.96742248535156},{"x":456.9536437988281,"y":126.1763916015625},{"x":507.0527038574219,"y":311.0063781738281},{"x":505.5854187011719,"y":283.8486328125},{"x":503.9902038574219,"y":255.0736083984375},{"x":502.64898681640625,"y":223.33261108398438},{"x":500.9817199707031,"y":190.17578125},{"x":499.5549011230469,"y":153.6851043701172},{"x":497.220458984375,"y":115.11642456054688},{"x":538.781494140625,"y":300.4125671386719},{"x":538.7106323242188,"y":273.01458740234375},{"x":538.3088989257812,"y":243.62026977539062},{"x":537.8553466796875,"y":212.34764099121094},{"x":537.698486328125,"y":178.67147827148438},{"x":537.1810302734375,"y":142.3944854736328},{"x":537.1196899414062,"y":103.39346313476562}],"reprojectionErrors":[{"x":-0.166534423828125,"y":-0.08447265625},{"x":-0.146942138671875,"y":0.101531982421875},{"x":-0.340362548828125,"y":-0.08526611328125},{"x":-0.1258544921875,"y":-0.223175048828125},{"x":-0.1739501953125,"y":-0.2197723388671875},{"x":0.197662353515625,"y":0.146942138671875},{"x":0.47216796875,"y":-0.13018798828125},{"x":-0.051849365234375,"y":0.00189208984375},{"x":-0.23077392578125,"y":-0.2164306640625},{"x":-0.159576416015625,"y":-0.21490478515625},{"x":-0.347259521484375,"y":0.126007080078125},{"x":-0.353790283203125,"y":-0.2263641357421875},{"x":-0.377960205078125,"y":-0.1110382080078125},{"x":-0.0841064453125,"y":-0.0737762451171875},{"x":-0.124542236328125,"y":-0.32342529296875},{"x":-0.103851318359375,"y":-0.1572265625},{"x":0.03466796875,"y":-0.181182861328125},{"x":0.03125,"y":-0.29248046875},{"x":0.211944580078125,"y":-0.245880126953125},{"x":0.080902099609375,"y":0.0571441650390625},{"x":0.1334228515625,"y":-0.1610260009765625},{"x":-0.257537841796875,"y":-0.2183837890625},{"x":-0.2103271484375,"y":0.00360107421875},{"x":-0.0499267578125,"y":0.01220703125},{"x":-0.168548583984375,"y":-0.0898895263671875},{"x":0.072723388671875,"y":-0.2462158203125},{"x":-0.533172607421875,"y":-0.08941650390625},{"x":-0.083465576171875,"y":-0.1873779296875},{"x":0.136932373046875,"y":-0.06341552734375},{"x":0.258544921875,"y":-0.171722412109375},{"x":0.16259765625,"y":-0.179473876953125},{"x":0.3271484375,"y":0.01361083984375},{"x":-0.20330810546875,"y":-0.2396087646484375},{"x":-0.106170654296875,"y":0.1242218017578125},{"x":-0.077423095703125,"y":0.05437469482421875},{"x":-0.12353515625,"y":0.03765869140625},{"x":-0.019622802734375,"y":-0.148345947265625},{"x":0.128143310546875,"y":-0.5649566650390625},{"x":-0.071075439453125,"y":-0.060577392578125},{"x":-0.047576904296875,"y":-0.4115753173828125},{"x":-0.379730224609375,"y":0.03924560546875},{"x":0.066802978515625,"y":-0.26633453369140625},{"x":0.100830078125,"y":-0.13519287109375},{"x":-0.13873291015625,"y":-0.1788330078125},{"x":-0.05908203125,"y":-0.06317138671875},{"x":0.0595703125,"y":-0.100311279296875},{"x":-0.13275146484375,"y":0.012603759765625},{"x":0.01959228515625,"y":0.2167816162109375},{"x":-0.302001953125,"y":0.33905029296875}],"optimisedCameraToObject":{"translation":{"x":-0.06295448592156398,"y":0.08889978128206316,"z":0.4794619718432196},"rotation":{"quaternion":{"W":0.5778248786214113,"X":0.31575855832579636,"Y":0.127262991959412,"Z":-0.7417675332391576}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img13.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":221.69142150878906,"y":300.1886901855469},{"x":222.46527099609375,"y":271.0504150390625},{"x":222.8351593017578,"y":240.07876586914062},{"x":223.26959228515625,"y":206.57762145996094},{"x":223.80258178710938,"y":170.25401306152344},{"x":224.8080291748047,"y":130.37973022460938},{"x":225.090576171875,"y":87.83250427246094},{"x":260.7861022949219,"y":298.69000244140625},{"x":262.3690185546875,"y":270.0607604980469},{"x":264.5486755371094,"y":239.7367401123047},{"x":266.8238525390625,"y":206.78282165527344},{"x":268.8758239746094,"y":171.3037567138672},{"x":271.31195068359375,"y":132.38333129882812},{"x":273.30474853515625,"y":90.837158203125},{"x":297.60589599609375,"y":297.21368408203125},{"x":300.9400329589844,"y":269.1746826171875},{"x":304.4596862792969,"y":239.0690155029297},{"x":307.9609680175781,"y":206.87820434570312},{"x":311.688232421875,"y":171.9759063720703},{"x":315.81756591796875,"y":134.1763458251953},{"x":320.27130126953125,"y":93.03238677978516},{"x":334.13519287109375,"y":295.7984313964844},{"x":338.3509216308594,"y":268.04718017578125},{"x":343.0600891113281,"y":238.522705078125},{"x":347.9466552734375,"y":206.8267822265625},{"x":352.90216064453125,"y":172.9291229248047},{"x":359.0777893066406,"y":135.42062377929688},{"x":364.7772216796875,"y":95.76215362548828},{"x":368.829833984375,"y":294.6060485839844},{"x":373.9856872558594,"y":267.216552734375},{"x":380.24725341796875,"y":238.5316162109375},{"x":386.1326599121094,"y":206.89576721191406},{"x":392.9770812988281,"y":173.7933349609375},{"x":400.19366455078125,"y":137.19754028320312},{"x":408.0281677246094,"y":97.83882141113281},{"x":402.8626403808594,"y":293.397705078125},{"x":409.3900146484375,"y":266.3202209472656},{"x":416.0580749511719,"y":237.7155303955078},{"x":423.4273681640625,"y":207.07528686523438},{"x":430.9909973144531,"y":174.4130859375},{"x":440.0686340332031,"y":138.2748260498047},{"x":449.2325439453125,"y":100.07513427734375},{"x":435.31817626953125,"y":291.7955322265625},{"x":442.9797668457031,"y":265.6045227050781},{"x":450.8791809082031,"y":237.6734619140625},{"x":459.1878356933594,"y":207.1299285888672},{"x":468.36700439453125,"y":175.0641632080078},{"x":478.47161865234375,"y":139.8020782470703},{"x":489.10455322265625,"y":102.16590881347656}],"reprojectionErrors":[{"x":0.3343963623046875,"y":-0.271270751953125},{"x":0.006683349609375,"y":-0.057891845703125},{"x":0.117767333984375,"y":-0.175872802734375},{"x":0.2032928466796875,"y":-0.185455322265625},{"x":0.2340240478515625,"y":-0.0921783447265625},{"x":-0.1583099365234375,"y":0.482513427734375},{"x":0.228302001953125,"y":0.248626708984375},{"x":-0.265655517578125,"y":-0.227386474609375},{"x":-0.037200927734375,"y":-0.082794189453125},{"x":-0.269378662109375,"y":-0.337432861328125},{"x":-0.445159912109375,"y":-0.2996368408203125},{"x":-0.227447509765625,"y":-0.356903076171875},{"x":-0.202117919921875,"y":0.0767669677734375},{"x":0.4835205078125,"y":-0.20243072509765625},{"x":0.16845703125,"y":-0.141265869140625},{"x":-0.07818603515625,"y":-0.159942626953125},{"x":-0.28302001953125,"y":-0.138671875},{"x":-0.21612548828125,"y":-0.2904205322265625},{"x":-0.09185791015625,"y":-0.2569732666015625},{"x":-0.05126953125,"y":-0.164764404296875},{"x":0.024383544921875,"y":0.0673980712890625},{"x":-0.28558349609375,"y":-0.054779052734375},{"x":-0.220184326171875,"y":0.053131103515625},{"x":-0.338592529296875,"y":-0.028472900390625},{"x":-0.29010009765625,"y":-0.121551513671875},{"x":0.073883056640625,"y":-0.450286865234375},{"x":-0.351165771484375,"y":0.098876953125},{"x":0.185516357421875,"y":-0.2803192138671875},{"x":-0.02557373046875,"y":-0.132720947265625},{"x":0.21697998046875,"y":0.015625},{"x":-0.262481689453125,"y":-0.4423675537109375},{"x":0.060211181640625,"y":-0.0608978271484375},{"x":-0.101348876953125,"y":-0.5660400390625},{"x":-0.103790283203125,"y":-0.211090087890625},{"x":-0.1270751953125,"y":-0.0528717041015625},{"x":-0.1700439453125,"y":-0.139007568359375},{"x":-0.25262451171875,"y":0.087860107421875},{"x":-0.025390625,"y":-0.001678466796875},{"x":-1.52587890625E-4,"y":-0.09918212890625},{"x":0.38623046875,"y":-0.4481048583984375},{"x":-0.121063232421875,"y":0.139984130859375},{"x":-0.018829345703125,"y":-0.05832672119140625},{"x":0.247314453125,"y":0.30157470703125},{"x":0.011138916015625,"y":0.021392822265625},{"x":0.0477294921875,"y":-0.3069000244140625},{"x":0.240081787109375,"y":-0.001556396484375},{"x":0.189422607421875,"y":-0.37164306640625},{"x":-0.087158203125,"y":0.00469970703125},{"x":-0.109100341796875,"y":0.01280975341796875}],"optimisedCameraToObject":{"translation":{"x":-0.14803134618985717,"y":0.03435954453002543,"z":0.46613706783576997},"rotation":{"quaternion":{"W":0.6823354998518218,"X":0.3499705246595619,"Y":0.14185342694752978,"Z":-0.6259524764506627}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img14.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":128.8193359375,"y":232.03421020507812},{"x":141.69044494628906,"y":206.0784149169922},{"x":155.53761291503906,"y":178.03823852539062},{"x":170.85655212402344,"y":146.86415100097656},{"x":187.83511352539062,"y":112.7492904663086},{"x":206.21925354003906,"y":74.6177749633789},{"x":172.7858428955078,"y":246.0005645751953},{"x":187.14730834960938,"y":221.37124633789062},{"x":202.56089782714844,"y":194.89793395996094},{"x":219.62840270996094,"y":165.4069061279297},{"x":238.2081756591797,"y":133.6314697265625},{"x":258.8237609863281,"y":98.0567855834961},{"x":281.4809265136719,"y":58.69950866699219},{"x":213.98338317871094,"y":259.02935791015625},{"x":229.82254028320312,"y":235.7659454345703},{"x":246.8004913330078,"y":210.47906494140625},{"x":264.8943786621094,"y":183.06935119628906},{"x":285.044189453125,"y":152.9588165283203},{"x":307.1773681640625,"y":119.56204223632812},{"x":331.650146484375,"y":82.94720458984375},{"x":253.132568359375,"y":271.61981201171875},{"x":270.10540771484375,"y":249.15467834472656},{"x":287.9201965332031,"y":225.55262756347656},{"x":307.40386962890625,"y":199.6800537109375},{"x":329.0587463378906,"y":171.06024169921875},{"x":352.8269348144531,"y":139.88975524902344},{"x":378.45611572265625,"y":105.61479187011719},{"x":290.0845642089844,"y":283.2516174316406},{"x":307.77392578125,"y":262.2010192871094},{"x":326.5614929199219,"y":239.79440307617188},{"x":347.58837890625,"y":214.83523559570312},{"x":370.0354309082031,"y":188.0342559814453},{"x":394.7102355957031,"y":158.73892211914062},{"x":421.73358154296875,"y":126.56830596923828},{"x":325.0890808105469,"y":294.5356750488281},{"x":343.9632568359375,"y":274.3666687011719},{"x":363.530029296875,"y":253.0194549560547},{"x":385.0899353027344,"y":229.59095764160156},{"x":408.6915588378906,"y":204.20619201660156},{"x":434.48577880859375,"y":176.2459716796875},{"x":462.5693664550781,"y":146.03135681152344},{"x":358.37957763671875,"y":305.0079650878906},{"x":377.4293518066406,"y":285.9749450683594},{"x":398.3611145019531,"y":265.2095031738281},{"x":420.78125,"y":243.20278930664062},{"x":445.0531005859375,"y":219.17079162597656},{"x":471.564697265625,"y":192.88790893554688},{"x":500.5176696777344,"y":164.17803955078125}],"reprojectionErrors":[{"x":0.6591644287109375,"y":-0.2232666015625},{"x":0.4605255126953125,"y":-0.1044158935546875},{"x":0.4600982666015625,"y":-0.286376953125},{"x":0.33502197265625,"y":-0.07073974609375},{"x":0.105987548828125,"y":-0.0742034912109375},{"x":0.2809295654296875,"y":0.263397216796875},{"x":0.197418212890625,"y":-0.3149871826171875},{"x":0.01092529296875,"y":-0.1623382568359375},{"x":0.0468292236328125,"y":-0.35443115234375},{"x":-0.1151123046875,"y":-0.02935791015625},{"x":-0.1154327392578125,"y":-0.2944488525390625},{"x":-0.214202880859375,"y":-0.08739471435546875},{"x":-0.0953369140625,"y":0.022396087646484375},{"x":0.1088714599609375,"y":-0.20892333984375},{"x":-0.23883056640625,"y":-0.1714324951171875},{"x":-0.3728485107421875,"y":-0.1241455078125},{"x":-0.08367919921875,"y":-0.2456512451171875},{"x":-0.088531494140625,"y":-0.2895660400390625},{"x":-0.047088623046875,"y":-0.06926727294921875},{"x":0.009552001953125,"y":-0.13692474365234375},{"x":-0.1318817138671875,"y":-0.343963623046875},{"x":-0.459197998046875,"y":0.048126220703125},{"x":-0.216400146484375,"y":-0.27996826171875},{"x":-0.041351318359375,"y":-0.4433135986328125},{"x":-0.212005615234375,"y":-0.2602691650390625},{"x":-0.402099609375,"y":-0.2803497314453125},{"x":-0.035675048828125,"y":-0.3754425048828125},{"x":-0.201416015625,"y":-0.1458740234375},{"x":-0.23345947265625,"y":-0.10308837890625},{"x":0.092864990234375,"y":-0.420989990234375},{"x":-0.1741943359375,"y":-0.12615966796875},{"x":0.008087158203125,"y":-0.19287109375},{"x":0.09820556640625,"y":-0.28216552734375},{"x":0.29437255859375,"y":-0.38910675048828125},{"x":-0.192840576171875,"y":-0.177154541015625},{"x":-0.5228271484375,"y":-0.02960205078125},{"x":-0.0567626953125,"y":-0.29412841796875},{"x":0.092803955078125,"y":-0.2685546875},{"x":0.098358154296875,"y":-0.3140411376953125},{"x":0.07073974609375,"y":-0.0909881591796875},{"x":0.225250244140625,"y":-0.2539215087890625},{"x":-0.198760986328125,"y":0.069671630859375},{"x":0.07257080078125,"y":-0.003387451171875},{"x":-0.027679443359375,"y":0.1796875},{"x":0.07958984375,"y":-0.0535430908203125},{"x":0.248260498046875,"y":-0.1313934326171875},{"x":0.34613037109375,"y":-0.0783843994140625},{"x":0.475311279296875,"y":-0.0152587890625}],"optimisedCameraToObject":{"translation":{"x":-0.19190377003576267,"y":-0.02127084777280399,"z":0.4012728762421166},"rotation":{"quaternion":{"W":0.779494566242866,"X":0.4026001951088417,"Y":0.20069457218144077,"Z":-0.4359162680986768}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img15.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":363.89569091796875,"y":477.9421081542969},{"x":337.60406494140625,"y":455.5654296875},{"x":309.97625732421875,"y":432.04150390625},{"x":280.59759521484375,"y":407.108154296875},{"x":249.45628356933594,"y":381.0322570800781},{"x":216.36166381835938,"y":352.95843505859375},{"x":181.16319274902344,"y":323.3760986328125},{"x":387.8879699707031,"y":443.8932800292969},{"x":362.6149597167969,"y":421.04736328125},{"x":336.1600036621094,"y":397.13592529296875},{"x":308.3136901855469,"y":371.9574279785156},{"x":278.7854919433594,"y":345.3088073730469},{"x":247.22349548339844,"y":316.88250732421875},{"x":213.96876525878906,"y":286.820556640625},{"x":410.738037109375,"y":411.72308349609375},{"x":386.656005859375,"y":388.27764892578125},{"x":361.3669128417969,"y":364.05078125},{"x":334.62457275390625,"y":338.3759460449219},{"x":306.60150146484375,"y":311.30767822265625},{"x":276.542236328125,"y":282.6142578125},{"x":244.87734985351562,"y":252.084228515625},{"x":432.8547668457031,"y":380.25897216796875},{"x":409.8225402832031,"y":356.78924560546875},{"x":385.7375183105469,"y":332.10784912109375},{"x":360.0956726074219,"y":306.04052734375},{"x":333.28192138671875,"y":278.6481628417969},{"x":304.82861328125,"y":249.48875427246094},{"x":274.5617980957031,"y":218.8278045654297},{"x":454.0780029296875,"y":350.27984619140625},{"x":432.01690673828125,"y":326.4764709472656},{"x":408.9326477050781,"y":301.5626525878906},{"x":384.58734130859375,"y":275.0774230957031},{"x":358.91064453125,"y":247.470458984375},{"x":331.7420654296875,"y":217.9922637939453},{"x":302.91571044921875,"y":186.9136505126953},{"x":474.8527526855469,"y":321.28546142578125},{"x":453.5667724609375,"y":297.1605224609375},{"x":431.3580017089844,"y":271.90667724609375},{"x":408.0592346191406,"y":245.06117248535156},{"x":383.6998596191406,"y":217.1850128173828},{"x":357.6435546875,"y":187.38978576660156},{"x":330.1816711425781,"y":156.1217041015625},{"x":494.603759765625,"y":293.3293762207031},{"x":474.12054443359375,"y":268.99664306640625},{"x":453.0230712890625,"y":243.4575958251953},{"x":430.62255859375,"y":216.53524780273438},{"x":407.20623779296875,"y":188.3256378173828},{"x":382.35577392578125,"y":158.3732147216797},{"x":356.1711120605469,"y":126.89205932617188}],"reprojectionErrors":[{"x":-0.112335205078125,"y":-0.345794677734375},{"x":-0.06842041015625,"y":-0.19561767578125},{"x":-0.148468017578125,"y":-0.13726806640625},{"x":-0.066375732421875,"y":-0.017730712890625},{"x":0.0453948974609375,"y":-0.226318359375},{"x":0.2153472900390625,"y":-0.04522705078125},{"x":0.410888671875,"y":-0.1192626953125},{"x":-0.285675048828125,"y":0.056427001953125},{"x":-0.11248779296875,"y":0.210662841796875},{"x":-0.124481201171875,"y":0.189727783203125},{"x":-0.230316162109375,"y":0.088043212890625},{"x":-0.27142333984375,"y":-0.011138916015625},{"x":-0.0439910888671875,"y":0.065399169921875},{"x":-0.055877685546875,"y":0.024261474609375},{"x":-0.1890869140625,"y":-0.15948486328125},{"x":-0.126556396484375,"y":0.179107666015625},{"x":-0.138519287109375,"y":0.059539794921875},{"x":-0.08721923828125,"y":0.04345703125},{"x":-0.2662353515625,"y":-0.04071044921875},{"x":-0.055572509765625,"y":-0.092254638671875},{"x":-0.0379791259765625,"y":-0.0469512939453125},{"x":-0.18133544921875,"y":0.106689453125},{"x":-0.15069580078125,"y":0.099700927734375},{"x":-0.269866943359375,"y":0.0682373046875},{"x":-0.1346435546875,"y":0.084014892578125},{"x":-0.241058349609375,"y":-0.028106689453125},{"x":-0.245635986328125,"y":0.04632568359375},{"x":-0.113494873046875,"y":-0.1011962890625},{"x":-0.055938720703125,"y":0.0091552734375},{"x":-0.036163330078125,"y":0.00701904296875},{"x":-0.122955322265625,"y":-0.1153564453125},{"x":-0.170379638671875,"y":0.002777099609375},{"x":-0.2103271484375,"y":-0.199554443359375},{"x":-0.196197509765625,"y":-0.09698486328125},{"x":-0.089569091796875,"y":-0.0990753173828125},{"x":-0.214935302734375,"y":-0.0137939453125},{"x":-0.0634765625,"y":0.014129638671875},{"x":-0.051513671875,"y":-0.0526123046875},{"x":-0.096649169921875,"y":0.1509552001953125},{"x":-0.322479248046875,"y":-0.0445556640625},{"x":-0.1973876953125,"y":0.1286163330078125},{"x":-0.129638671875,"y":0.0896759033203125},{"x":-0.04327392578125,"y":-0.073211669921875},{"x":0.162689208984375,"y":-0.095123291015625},{"x":-0.016845703125,"y":-0.125762939453125},{"x":0.0284423828125,"y":-0.08343505859375},{"x":-0.07550048828125,"y":-0.169708251953125},{"x":-0.00677490234375,"y":-0.046173095703125},{"x":0.02734375,"y":-0.05738067626953125}],"optimisedCameraToObject":{"translation":{"x":-0.022135018974242134,"y":0.16005134215092787,"z":0.42957831638407207},"rotation":{"quaternion":{"W":0.34764224981098996,"X":0.2784351069385136,"Y":-0.07302978076487111,"Z":-0.8923482551627064}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img16.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":371.47454833984375,"y":456.0576477050781},{"x":361.9463806152344,"y":409.755615234375},{"x":352.04510498046875,"y":364.0506286621094},{"x":342.7134094238281,"y":319.0185241699219},{"x":333.0418395996094,"y":275.0315856933594},{"x":324.03448486328125,"y":231.62362670898438},{"x":315.08154296875,"y":188.98597717285156},{"x":414.3829345703125,"y":448.90557861328125},{"x":403.8133239746094,"y":400.9820556640625},{"x":393.77410888671875,"y":354.2945556640625},{"x":383.3441162109375,"y":308.5827941894531},{"x":373.5011291503906,"y":263.7982177734375},{"x":363.8036193847656,"y":219.042236328125},{"x":354.0941467285156,"y":175.64903259277344},{"x":458.6427307128906,"y":440.9432067871094},{"x":447.6053466796875,"y":392.1411437988281},{"x":437.1440734863281,"y":344.3612976074219},{"x":425.920166015625,"y":297.4424133300781},{"x":415.63763427734375,"y":251.10206604003906},{"x":404.95379638671875,"y":205.92068481445312},{"x":394.551025390625,"y":161.488525390625},{"x":505.8532409667969,"y":432.2632141113281},{"x":494.2593078613281,"y":382.54095458984375},{"x":482.2918395996094,"y":334.1191711425781},{"x":470.29974365234375,"y":285.4431457519531},{"x":459.73052978515625,"y":238.64024353027344},{"x":449.1366882324219,"y":192.1394500732422},{"x":437.708984375,"y":146.63104248046875},{"x":555.4942626953125,"y":423.8999938964844},{"x":542.7362670898438,"y":372.83233642578125},{"x":530.123779296875,"y":322.5932922363281},{"x":517.9358520507812,"y":273.2138366699219},{"x":506.0396423339844,"y":225.0269012451172},{"x":494.1130065917969,"y":177.46600341796875},{"x":482.9423828125,"y":130.7449951171875},{"x":608.1504516601562,"y":415.12646484375},{"x":594.6188354492188,"y":362.04595947265625},{"x":581.01953125,"y":310.4835510253906},{"x":567.9055786132812,"y":259.8913879394531},{"x":555.0604858398438,"y":211.06338500976562},{"x":542.9880981445312,"y":161.853271484375},{"x":530.4802856445312,"y":114.29183197021484},{"x":663.278564453125,"y":405.24957275390625},{"x":648.9782104492188,"y":351.1282653808594},{"x":634.858154296875,"y":298.228271484375},{"x":620.8067626953125,"y":246.12586975097656},{"x":607.0422973632812,"y":195.45692443847656},{"x":593.87548828125,"y":145.31231689453125},{"x":580.6283569335938,"y":96.33258819580078}],"reprojectionErrors":[{"x":0.402313232421875,"y":0.16754150390625},{"x":0.10052490234375,"y":0.008392333984375},{"x":0.330108642578125,"y":0.052490234375},{"x":0.14337158203125,"y":0.19927978515625},{"x":0.44500732421875,"y":0.0526123046875},{"x":0.22637939453125,"y":0.0558929443359375},{"x":0.0928955078125,"y":-0.0042266845703125},{"x":-0.068695068359375,"y":-0.144256591796875},{"x":0.047515869140625,"y":0.219573974609375},{"x":-0.192169189453125,"y":0.186553955078125},{"x":0.127899169921875,"y":-0.009429931640625},{"x":0.024566650390625,"y":-0.3453369140625},{"x":-0.065765380859375,"y":0.0530548095703125},{"x":0.009429931640625,"y":-0.171875},{"x":0.300994873046875,"y":-0.026702880859375},{"x":0.208953857421875,"y":0.06182861328125},{"x":-0.266510009765625,"y":0.009246826171875},{"x":0.20703125,"y":-0.051544189453125},{"x":-0.080413818359375,"y":0.1346435546875},{"x":0.208099365234375,"y":-0.0387420654296875},{"x":0.3846435546875,"y":-0.18701171875},{"x":0.094146728515625,"y":0.3958740234375},{"x":-0.17584228515625,"y":0.191162109375},{"x":0.14056396484375,"y":-0.38763427734375},{"x":0.6875,"y":0.1837158203125},{"x":0.010650634765625,"y":-0.2514190673828125},{"x":-0.448944091796875,"y":-0.14996337890625},{"x":0.11175537109375,"y":-0.2290496826171875},{"x":0.0338134765625,"y":0.053802490234375},{"x":0.1279296875,"y":-0.08319091796875},{"x":0.31219482421875,"y":-0.073486328125},{"x":0.29949951171875,"y":0.0191650390625},{"x":0.215118408203125,"y":-0.1696624755859375},{"x":0.373931884765625,"y":-0.1034698486328125},{"x":-0.017547607421875,"y":-0.02496337890625},{"x":-0.23828125,"y":-0.365203857421875},{"x":-0.24365234375,"y":0.163482666015625},{"x":0.07977294921875,"y":0.202423095703125},{"x":0.169921875,"y":0.26409912109375},{"x":0.23468017578125,"y":-0.479278564453125},{"x":-0.23797607421875,"y":0.086212158203125},{"x":-0.0478515625,"y":-0.10117340087890625},{"x":0.07501220703125,"y":-0.21221923828125},{"x":-0.1170654296875,"y":-0.065185546875},{"x":-0.1995849609375,"y":-0.053466796875},{"x":-0.07110595703125,"y":0.2083740234375},{"x":0.04022216796875,"y":0.04791259765625},{"x":-0.185546875,"y":0.3393707275390625},{"x":-0.079345703125,"y":0.40883636474609375}],"optimisedCameraToObject":{"translation":{"x":-0.03275125711412719,"y":0.1273676349573531,"z":0.3767822852515672},"rotation":{"quaternion":{"W":0.6035299205878326,"X":-0.16435445445844546,"Y":0.1055547011938555,"Z":-0.7730442764232764}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img17.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":255.92227172851562,"y":371.9599914550781},{"x":250.83261108398438,"y":331.1030578613281},{"x":245.38430786132812,"y":290.5831298828125},{"x":240.3695068359375,"y":249.9293212890625},{"x":235.1809539794922,"y":209.56466674804688},{"x":230.15940856933594,"y":169.4456787109375},{"x":225.00128173828125,"y":129.22972106933594},{"x":292.0305480957031,"y":368.1048278808594},{"x":286.998779296875,"y":326.4951477050781},{"x":281.58355712890625,"y":285.2678527832031},{"x":276.055419921875,"y":243.87893676757812},{"x":270.97393798828125,"y":202.92807006835938},{"x":265.8970642089844,"y":161.53250122070312},{"x":260.3387451171875,"y":120.88822174072266},{"x":329.61492919921875,"y":364.20977783203125},{"x":324.0916748046875,"y":321.8574523925781},{"x":318.302978515625,"y":279.5847473144531},{"x":313.0848693847656,"y":237.26657104492188},{"x":307.65704345703125,"y":195.21185302734375},{"x":302.27197265625,"y":153.8026123046875},{"x":296.6943359375,"y":111.83676147460938},{"x":368.60302734375,"y":360.3734436035156},{"x":362.9759521484375,"y":316.82525634765625},{"x":357.582763671875,"y":273.8042297363281},{"x":351.75372314453125,"y":230.84141540527344},{"x":346.1147155761719,"y":188.0590362548828},{"x":340.10498046875,"y":145.00839233398438},{"x":334.9411315917969,"y":102.54414367675781},{"x":409.62896728515625,"y":356.3480529785156},{"x":403.552734375,"y":312.1590881347656},{"x":397.63983154296875,"y":267.98431396484375},{"x":391.9539489746094,"y":224.18540954589844},{"x":385.966552734375,"y":180.14523315429688},{"x":380.2233581542969,"y":136.33714294433594},{"x":374.0210876464844,"y":92.4462890625},{"x":452.2801208496094,"y":351.94403076171875},{"x":446.1499328613281,"y":306.5798645019531},{"x":440.1190185546875,"y":261.4664001464844},{"x":433.9687805175781,"y":216.5105438232422},{"x":428.1037902832031,"y":172.06724548339844},{"x":422.01080322265625,"y":126.95559692382812},{"x":416.0359802246094,"y":82.30215454101562},{"x":496.5943603515625,"y":347.0357666015625},{"x":490.3442077636719,"y":301.0941162109375},{"x":483.81689453125,"y":254.87655639648438},{"x":477.9454650878906,"y":209.01657104492188},{"x":471.4839782714844,"y":163.00772094726562},{"x":465.14056396484375,"y":117.92872619628906},{"x":459.079345703125,"y":71.69132232666016}],"reprojectionErrors":[{"x":0.24468994140625,"y":-0.28070068359375},{"x":0.170013427734375,"y":-0.116912841796875},{"x":0.45880126953125,"y":-0.15887451171875},{"x":0.31842041015625,"y":0.06005859375},{"x":0.355682373046875,"y":0.112762451171875},{"x":0.229339599609375,"y":0.038665771484375},{"x":0.2425384521484375,"y":0.1763763427734375},{"x":0.125030517578125,"y":-0.065277099609375},{"x":-0.173187255859375,"y":0.016815185546875},{"x":-0.081390380859375,"y":-0.14697265625},{"x":0.12933349609375,"y":-0.016998291015625},{"x":-0.10107421875,"y":-0.1972503662109375},{"x":-0.331085205078125,"y":0.1907958984375},{"x":-0.075103759765625,"y":-0.053070068359375},{"x":0.036376953125,"y":0.040496826171875},{"x":0.0543212890625,"y":-0.00592041015625},{"x":0.3460693359375,"y":0.010162353515625},{"x":0.075103759765625,"y":0.209259033203125},{"x":0.021148681640625,"y":0.2779693603515625},{"x":-0.068817138671875,"y":-0.1701812744140625},{"x":0.0400390625,"y":0.06252288818359375},{"x":0.153717041015625,"y":-0.072174072265625},{"x":0.089569091796875,"y":0.16693115234375},{"x":-0.198089599609375,"y":0.026947021484375},{"x":-0.0400390625,"y":-0.027862548828125},{"x":-0.062774658203125,"y":-0.124481201171875},{"x":0.293853759765625,"y":0.18115234375},{"x":-0.187255859375,"y":0.0298004150390625},{"x":-0.045013427734375,"y":-0.16668701171875},{"x":0.142608642578125,"y":-0.239013671875},{"x":0.17950439453125,"y":-0.171051025390625},{"x":0.0013427734375,"y":-0.3294219970703125},{"x":0.136077880859375,"y":-0.1019439697265625},{"x":0.037353515625,"y":0.0331878662109375},{"x":0.407867431640625,"y":0.385986328125},{"x":-0.02447509765625,"y":-0.06561279296875},{"x":0.0072021484375,"y":0.040191650390625},{"x":-0.04541015625,"y":0.056640625},{"x":0.035675048828125,"y":0.0716400146484375},{"x":-0.15484619140625,"y":-0.274993896484375},{"x":-0.104339599609375,"y":0.19260406494140625},{"x":-0.15960693359375,"y":0.34279632568359375},{"x":0.31207275390625,"y":0.343292236328125},{"x":0.240142822265625,"y":-0.0185546875},{"x":0.4630126953125,"y":0.0642242431640625},{"x":0.046905517578125,"y":-0.0473480224609375},{"x":0.237091064453125,"y":0.1476898193359375},{"x":0.32470703125,"y":-0.43468475341796875},{"x":0.144927978515625,"y":0.2884674072265625}],"optimisedCameraToObject":{"translation":{"x":-0.10965692629299488,"y":0.08635579281798106,"z":0.4316409539931316},"rotation":{"quaternion":{"W":0.6470956324385401,"X":-0.12310527462232564,"Y":0.12129835253173392,"Z":-0.7425624845844387}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img18.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":199.0754852294922,"y":469.215087890625},{"x":190.6791534423828,"y":425.8723449707031},{"x":182.0411376953125,"y":383.112548828125},{"x":174.13853454589844,"y":341.0018005371094},{"x":165.97364807128906,"y":299.9004211425781},{"x":157.95103454589844,"y":258.86859130859375},{"x":150.04771423339844,"y":218.75074768066406},{"x":237.8850555419922,"y":461.00537109375},{"x":229.13961791992188,"y":416.78985595703125},{"x":220.3484649658203,"y":373.8474426269531},{"x":211.69705200195312,"y":331.039306640625},{"x":203.11280822753906,"y":289.1053161621094},{"x":194.6079864501953,"y":247.84075927734375},{"x":186.2067413330078,"y":207.10385131835938},{"x":277.4243469238281,"y":452.14569091796875},{"x":268.0755615234375,"y":407.5162048339844},{"x":259.0599060058594,"y":363.821044921875},{"x":250.0270233154297,"y":320.92401123046875},{"x":241.00015258789062,"y":278.30078125},{"x":232.09234619140625,"y":236.64503479003906},{"x":223.5209197998047,"y":195.2038116455078},{"x":318.5873718261719,"y":443.7076721191406},{"x":308.82196044921875,"y":397.99700927734375},{"x":299.0360107421875,"y":353.8716735839844},{"x":289.9013671875,"y":310.0795593261719},{"x":280.1575012207031,"y":267.25927734375},{"x":270.956298828125,"y":224.76071166992188},{"x":261.6512145996094,"y":182.9397735595703},{"x":361.00286865234375,"y":434.1965637207031},{"x":350.25482177734375,"y":388.46722412109375},{"x":339.95458984375,"y":343.3843994140625},{"x":330.1349792480469,"y":299.1314392089844},{"x":320.50128173828125,"y":255.48220825195312},{"x":310.52423095703125,"y":212.39439392089844},{"x":300.7534484863281,"y":170.56988525390625},{"x":404.22259521484375,"y":424.9312744140625},{"x":393.33892822265625,"y":378.091064453125},{"x":382.8352966308594,"y":332.7283935546875},{"x":372.2806701660156,"y":287.6020202636719},{"x":361.94287109375,"y":243.56411743164062},{"x":351.7824401855469,"y":200.02598571777344},{"x":341.7528381347656,"y":157.2625274658203},{"x":449.0185546875,"y":415.0521240234375},{"x":437.5583190917969,"y":367.4244689941406},{"x":426.2322692871094,"y":321.7363586425781},{"x":415.22100830078125,"y":276.80181884765625},{"x":404.1714172363281,"y":231.65573120117188},{"x":393.8834533691406,"y":187.2362518310547},{"x":383.0849914550781,"y":143.85829162597656}],"reprojectionErrors":[{"x":0.3704376220703125,"y":-0.30914306640625},{"x":0.289306640625,"y":-0.189483642578125},{"x":0.5640869140625,"y":-0.004058837890625},{"x":0.2143402099609375,"y":0.162689208984375},{"x":0.234588623046875,"y":-0.06732177734375},{"x":0.2171783447265625,"y":0.228668212890625},{"x":0.1821136474609375,"y":0.1897125244140625},{"x":0.04669189453125,"y":-0.416900634765625},{"x":-0.10772705078125,"y":-0.01312255859375},{"x":-0.0928802490234375,"y":-0.215301513671875},{"x":-0.0978240966796875,"y":0.09619140625},{"x":-0.0535125732421875,"y":0.163055419921875},{"x":0.02447509765625,"y":0.172271728515625},{"x":0.1087188720703125,"y":0.248443603515625},{"x":0.16796875,"y":-0.12554931640625},{"x":0.17205810546875,"y":0.085540771484375},{"x":-0.023468017578125,"y":0.048614501953125},{"x":-0.0721435546875,"y":-0.12005615234375},{"x":-0.00103759765625,"y":0.084686279296875},{"x":0.0731658935546875,"y":-0.04931640625},{"x":-0.0703887939453125,"y":0.2130584716796875},{"x":-0.09881591796875,"y":-0.519744873046875},{"x":-0.147064208984375,"y":0.14697265625},{"x":-0.030517578125,"y":-0.06524658203125},{"x":-0.425262451171875,"y":0.07501220703125},{"x":-0.074951171875,"y":-0.090850830078125},{"x":-0.13543701171875,"y":0.068023681640625},{"x":0.035980224609375,"y":0.1772003173828125},{"x":-0.3172607421875,"y":-0.11859130859375},{"x":0.122344970703125,"y":-0.07855224609375},{"x":0.26995849609375,"y":0.042449951171875},{"x":0.08807373046875,"y":0.039520263671875},{"x":-0.13311767578125,"y":0.1179046630859375},{"x":0.13134765625,"y":0.2999114990234375},{"x":0.32763671875,"y":-0.135650634765625},{"x":0.03057861328125,"y":-0.255950927734375},{"x":0.083343505859375,"y":0.2288818359375},{"x":-0.07574462890625,"y":-0.01416015625},{"x":-0.02069091796875,"y":0.233551025390625},{"x":-0.0242919921875,"y":0.098175048828125},{"x":-0.051788330078125,"y":0.147491455078125},{"x":-0.061187744140625,"y":0.086517333984375},{"x":0.247528076171875,"y":-0.088104248046875},{"x":0.3245849609375,"y":0.496429443359375},{"x":0.44903564453125,"y":-0.085723876953125},{"x":0.4346923828125,"y":-0.672119140625},{"x":0.62933349609375,"y":-0.3203277587890625},{"x":0.227813720703125,"y":0.009735107421875},{"x":0.49737548828125,"y":-0.017852783203125}],"optimisedCameraToObject":{"translation":{"x":-0.13498526728177662,"y":0.1419306272383528,"z":0.4012068486133499},"rotation":{"quaternion":{"W":0.6082579561435724,"X":-0.12018498945540622,"Y":0.05753774228200281,"Z":-0.7824750700889693}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img19.png"},{"locationInObjectSpace":[{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":246.0367889404297,"y":511.3815002441406},{"x":232.08111572265625,"y":461.0760498046875},{"x":218.39796447753906,"y":412.0758361816406},{"x":204.98626708984375,"y":363.95965576171875},{"x":191.98338317871094,"y":317.07843017578125},{"x":308.7626647949219,"y":547.3294677734375},{"x":293.9015197753906,"y":496.0552673339844},{"x":279.18023681640625,"y":445.6769714355469},{"x":264.9890441894531,"y":396.8298034667969},{"x":251.05467224121094,"y":348.09552001953125},{"x":237.20941162109375,"y":301.1927795410156},{"x":357.1434631347656,"y":532.4302978515625},{"x":341.935302734375,"y":480.8160095214844},{"x":326.42254638671875,"y":430.1467590332031},{"x":311.9454345703125,"y":380.9476318359375},{"x":297.1696472167969,"y":332.4278564453125},{"x":282.755615234375,"y":285.23199462890625},{"x":406.9462585449219,"y":516.97705078125},{"x":390.5466003417969,"y":465.3791198730469},{"x":375.0066833496094,"y":414.38397216796875},{"x":359.4614562988281,"y":364.8647155761719},{"x":344.314697265625,"y":316.4855041503906},{"x":329.1365661621094,"y":269.08990478515625},{"x":456.93060302734375,"y":501.642333984375},{"x":439.86236572265625,"y":449.37054443359375},{"x":423.306884765625,"y":398.79541015625},{"x":407.1817932128906,"y":348.95556640625},{"x":391.4373779296875,"y":300.31134033203125},{"x":376.05517578125,"y":252.9162139892578},{"x":507.88665771484375,"y":485.7825622558594},{"x":490.3066711425781,"y":433.8955993652344},{"x":472.9918212890625,"y":382.3048095703125},{"x":456.3659973144531,"y":332.7596435546875},{"x":439.7148132324219,"y":283.8486022949219},{"x":423.6504211425781,"y":236.18128967285156},{"x":578.139404296875,"y":524.2297973632812},{"x":559.6220092773438,"y":470.1282653808594},{"x":540.9761962890625,"y":417.748291015625},{"x":523.1632080078125,"y":366.23486328125},{"x":505.713134765625,"y":316.3343505859375},{"x":488.2321472167969,"y":267.385986328125},{"x":471.8785400390625,"y":219.29000854492188}],"reprojectionErrors":[{"x":0.2454376220703125,"y":-0.370330810546875},{"x":0.255767822265625,"y":-0.14459228515625},{"x":0.2826995849609375,"y":-0.146484375},{"x":0.3166046142578125,"y":0.005584716796875},{"x":0.209930419921875,"y":-0.077178955078125},{"x":-0.17449951171875,"y":0.0272216796875},{"x":-0.19171142578125,"y":-0.09136962890625},{"x":-0.030670166015625,"y":0.024871826171875},{"x":-0.093597412109375,"y":-0.3016357421875},{"x":-0.118560791015625,"y":0.30706787109375},{"x":0.0512847900390625,"y":0.0938720703125},{"x":0.182891845703125,"y":-0.12945556640625},{"x":-0.13726806640625,"y":-0.104888916015625},{"x":0.183685302734375,"y":0.117095947265625},{"x":-0.207183837890625,"y":-0.03167724609375},{"x":0.012298583984375,"y":0.1986083984375},{"x":0.17022705078125,"y":0.1243896484375},{"x":-0.18115234375,"y":0.0589599609375},{"x":0.022186279296875,"y":-0.133056640625},{"x":-0.278594970703125,"y":0.22662353515625},{"x":-0.23193359375,"y":0.2210693359375},{"x":-0.25445556640625,"y":0.14447021484375},{"x":0.071441650390625,"y":0.1136474609375},{"x":-0.002655029296875,"y":-0.08740234375},{"x":0.18243408203125,"y":0.1910400390625},{"x":0.230255126953125,"y":-0.060455322265625},{"x":0.2088623046875,"y":0.074951171875},{"x":0.154327392578125,"y":0.094635009765625},{"x":0.072113037109375,"y":-0.095184326171875},{"x":-0.047332763671875,"y":0.0677490234375},{"x":-0.05694580078125,"y":-0.245330810546875},{"x":0.064453125,"y":0.32470703125},{"x":-0.12225341796875,"y":-0.016845703125},{"x":0.0828857421875,"y":0.098480224609375},{"x":0.053955078125,"y":0.020111083984375},{"x":0.13641357421875,"y":-0.66448974609375},{"x":-0.09735107421875,"y":-0.213775634765625},{"x":0.23193359375,"y":-0.243896484375},{"x":0.14605712890625,"y":0.05169677734375},{"x":0.09869384765625,"y":-0.1195068359375},{"x":0.46844482421875,"y":-0.14044189453125},{"x":0.082366943359375,"y":0.046966552734375}],"optimisedCameraToObject":{"translation":{"x":-0.07688444090161399,"y":0.19531347450613365,"z":0.33056727642306144},"rotation":{"quaternion":{"W":0.5814181968796966,"X":-0.08740355445380782,"Y":-0.004523913184400189,"Z":-0.8088838193557233}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/2948752f-8bce-4d9d-b759-ff887aa4f80e/imgs/800x600/img20.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/vision_settings/Camera Calibrations/6-800-600.json b/vision_settings/Camera Calibrations/6-800-600.json new file mode 100644 index 00000000..2f5b5c08 --- /dev/null +++ b/vision_settings/Camera Calibrations/6-800-600.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[682.4034410766624,0.0,411.7650197284614,0.0,682.4677513351877,292.09023622213573,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04181060440020393,-0.06444067485335024,8.494288134628351E-4,3.3585864027231495E-4,0.02190089192398146,-0.0015077997656131117,0.0025478913329049957,-8.703390881038168E-4]},"calobjectWarp":[6.37802568212424E-5,7.829560376491282E-5],"observations":[{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":371.0797119140625,"y":516.9478149414062},{"x":353.6139831542969,"y":456.0564880371094},{"x":336.4538269042969,"y":397.082275390625},{"x":320.1540832519531,"y":339.737060546875},{"x":304.11834716796875,"y":283.3084411621094},{"x":287.9603576660156,"y":227.59988403320312},{"x":272.1964416503906,"y":173.52574157714844},{"x":416.222412109375,"y":495.7750244140625},{"x":399.25775146484375,"y":438.8329772949219},{"x":382.7452087402344,"y":383.1850891113281},{"x":366.96075439453125,"y":328.9510498046875},{"x":350.83062744140625,"y":276.14044189453125},{"x":335.369140625,"y":223.6012725830078},{"x":319.90802001953125,"y":172.31883239746094},{"x":455.95703125,"y":477.1337890625},{"x":439.568603515625,"y":423.23773193359375},{"x":423.5888366699219,"y":371.016845703125},{"x":407.9009094238281,"y":319.21356201171875},{"x":392.3096923828125,"y":269.2051086425781},{"x":377.30523681640625,"y":219.6044158935547},{"x":362.8040466308594,"y":171.18580627441406},{"x":492.3589172363281,"y":460.3059997558594},{"x":476.3328552246094,"y":409.2121276855469},{"x":460.6966857910156,"y":359.7004089355469},{"x":445.5496826171875,"y":310.81365966796875},{"x":430.5770263671875,"y":263.2201843261719},{"x":415.775634765625,"y":215.86920166015625},{"x":401.3372802734375,"y":169.95755004882812},{"x":524.97998046875,"y":445.20196533203125},{"x":509.222900390625,"y":396.94171142578125},{"x":494.30865478515625,"y":349.6432800292969},{"x":479.3509826660156,"y":303.39324951171875},{"x":464.8659973144531,"y":257.89947509765625},{"x":450.3524475097656,"y":212.57296752929688},{"x":436.3758544921875,"y":168.647705078125},{"x":554.7373657226562,"y":431.5567626953125},{"x":539.5224609375,"y":385.2394714355469},{"x":524.751220703125,"y":340.3907470703125},{"x":510.24749755859375,"y":296.1210021972656},{"x":496.1311340332031,"y":252.6969757080078},{"x":482.3102111816406,"y":209.81382751464844},{"x":468.6264953613281,"y":167.64535522460938},{"x":566.9793090820312,"y":375.02008056640625},{"x":552.7638549804688,"y":332.07489013671875},{"x":538.5175170898438,"y":289.3097229003906},{"x":524.9800415039062,"y":248.1988983154297},{"x":511.21868896484375,"y":206.9740753173828},{"x":498.0646667480469,"y":166.72755432128906}],"reprojectionErrors":[{"x":-0.122283935546875,"y":-0.45135498046875},{"x":-0.035430908203125,"y":0.240814208984375},{"x":0.1309814453125,"y":0.3004150390625},{"x":-0.191375732421875,"y":-0.02978515625},{"x":-0.4190673828125,"y":-0.0806884765625},{"x":-0.178131103515625,"y":0.30291748046875},{"x":0.003265380859375,"y":0.167205810546875},{"x":-0.3408203125,"y":-0.186614990234375},{"x":-0.240814208984375,"y":0.140533447265625},{"x":-0.23834228515625,"y":0.314056396484375},{"x":-0.621246337890625,"y":0.17596435546875},{"x":-0.32708740234375,"y":-0.32000732421875},{"x":-0.381011962890625,"y":-0.056854248046875},{"x":-0.125152587890625,"y":-0.053497314453125},{"x":0.056365966796875,"y":-0.21685791015625},{"x":0.085693359375,"y":0.245269775390625},{"x":0.033660888671875,"y":0.0516357421875},{"x":0.006622314453125,"y":0.42718505859375},{"x":0.189697265625,"y":-0.036651611328125},{"x":0.083251953125,"y":0.0171661376953125},{"x":-0.238372802734375,"y":-0.214447021484375},{"x":-0.272369384765625,"y":-0.16632080078125},{"x":-0.113861083984375,"y":0.3355712890625},{"x":-0.04241943359375,"y":0.171905517578125},{"x":-0.16650390625,"y":0.271820068359375},{"x":-0.18017578125,"y":-0.05999755859375},{"x":-0.088836669921875,"y":0.2013397216796875},{"x":-0.09246826171875,"y":-0.1659088134765625},{"x":-0.28765869140625,"y":-0.221282958984375},{"x":0.076202392578125,"y":0.00128173828125},{"x":-0.121795654296875,"y":0.090606689453125},{"x":-0.003570556640625,"y":-0.064178466796875},{"x":-0.0931396484375,"y":-0.19439697265625},{"x":0.1031494140625,"y":0.2664337158203125},{"x":0.012481689453125,"y":0.0626373291015625},{"x":-0.42498779296875,"y":-0.34161376953125},{"x":-0.14776611328125,"y":0.24609375},{"x":-0.05279541015625,"y":0.117950439453125},{"x":0.02862548828125,"y":0.142242431640625},{"x":-0.03033447265625,"y":0.031768798828125},{"x":-0.144561767578125,"y":0.0716552734375},{"x":-0.162384033203125,"y":0.0690765380859375},{"x":-0.1376953125,"y":0.004241943359375},{"x":-0.18011474609375,"y":0.00244140625},{"x":0.04541015625,"y":0.48870849609375},{"x":-0.2071533203125,"y":-0.029327392578125},{"x":-0.011138916015625,"y":0.199310302734375},{"x":-0.2037353515625,"y":0.065521240234375}],"optimisedCameraToObject":{"translation":{"x":-0.028024441065923715,"y":0.12024848748171695,"z":0.26155199465155166},"rotation":{"quaternion":{"W":0.5710224788065738,"X":0.1669686172726597,"Y":-0.3210867368590698,"Z":-0.7368569175605576}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":275.9060363769531,"y":514.2431030273438},{"x":257.94732666015625,"y":448.3424377441406},{"x":240.2172393798828,"y":384.6665954589844},{"x":222.92088317871094,"y":321.9885559082031},{"x":205.8141326904297,"y":261.0025634765625},{"x":189.1824493408203,"y":200.99713134765625},{"x":172.96287536621094,"y":142.8405303955078},{"x":331.7901916503906,"y":491.0014343261719},{"x":314.1025085449219,"y":429.36767578125},{"x":296.9088439941406,"y":369.46075439453125},{"x":280.25927734375,"y":310.93475341796875},{"x":263.5113220214844,"y":253.8998565673828},{"x":247.06448364257812,"y":197.04800415039062},{"x":231.1529998779297,"y":142.09959411621094},{"x":380.9213562011719,"y":470.6441650390625},{"x":363.587890625,"y":412.6094665527344},{"x":346.8662109375,"y":356.3398742675781},{"x":330.3708190917969,"y":300.8206481933594},{"x":314.15478515625,"y":246.698486328125},{"x":298.4856262207031,"y":193.82310485839844},{"x":282.9474182128906,"y":141.40403747558594},{"x":425.1405334472656,"y":452.3320617675781},{"x":408.27154541015625,"y":397.451171875},{"x":391.9422912597656,"y":344.2025146484375},{"x":376.0014343261719,"y":291.88922119140625},{"x":360.1016845703125,"y":240.55984497070312},{"x":345.0812072753906,"y":190.33689880371094},{"x":329.6077575683594,"y":140.64498901367188},{"x":464.8293151855469,"y":436.0399475097656},{"x":448.2729797363281,"y":384.09844970703125},{"x":432.515869140625,"y":333.51776123046875},{"x":416.8027648925781,"y":283.6606750488281},{"x":401.5628662109375,"y":235.1351318359375},{"x":386.42156982421875,"y":187.13009643554688},{"x":371.62139892578125,"y":139.7620849609375},{"x":500.9114990234375,"y":421.1900329589844},{"x":484.904296875,"y":371.8652648925781},{"x":469.3334045410156,"y":323.835693359375},{"x":453.9981689453125,"y":276.2973937988281},{"x":439.2430419921875,"y":230.11550903320312},{"x":424.7178039550781,"y":184.1803436279297},{"x":410.0625,"y":139.21884155273438},{"x":533.496826171875,"y":407.85308837890625},{"x":517.9310302734375,"y":360.7680358886719},{"x":502.79766845703125,"y":314.99871826171875},{"x":487.99169921875,"y":269.82403564453125},{"x":473.1626892089844,"y":225.1503143310547},{"x":459.0385437011719,"y":181.51040649414062},{"x":445.07977294921875,"y":138.4457244873047}],"reprojectionErrors":[{"x":0.060821533203125,"y":-0.41217041015625},{"x":-0.104888916015625,"y":0.121612548828125},{"x":-0.0708465576171875,"y":-0.067535400390625},{"x":-0.058319091796875,"y":0.190521240234375},{"x":0.1614227294921875,"y":0.1474609375},{"x":0.2882843017578125,"y":0.463409423828125},{"x":0.371337890625,"y":0.221099853515625},{"x":-0.3004150390625,"y":-0.080780029296875},{"x":-0.28631591796875,"y":0.26153564453125},{"x":-0.370880126953125,"y":0.203094482421875},{"x":-0.6182861328125,"y":0.042144775390625},{"x":-0.399566650390625,"y":-0.3768768310546875},{"x":-0.1270599365234375,"y":0.21075439453125},{"x":-0.047332763671875,"y":0.0433349609375},{"x":-0.093597412109375,"y":-0.07733154296875},{"x":0.030853271484375,"y":0.26251220703125},{"x":-0.0909423828125,"y":0.0166015625},{"x":-0.08587646484375,"y":0.159423828125},{"x":-0.018951416015625,"y":0.0056610107421875},{"x":-0.16900634765625,"y":-0.3311614990234375},{"x":-0.13104248046875,"y":-0.095855712890625},{"x":-0.174102783203125,"y":0.030059814453125},{"x":-0.04766845703125,"y":0.413299560546875},{"x":-0.12225341796875,"y":0.220062255859375},{"x":-0.257537841796875,"y":0.11273193359375},{"x":-0.116790771484375,"y":0.0097808837890625},{"x":-0.5482177734375,"y":-0.2429046630859375},{"x":-0.22930908203125,"y":-0.100250244140625},{"x":-0.136810302734375,"y":-0.058624267578125},{"x":0.1378173828125,"y":0.2459716796875},{"x":-0.072296142578125,"y":0.14031982421875},{"x":-0.021728515625,"y":0.23199462890625},{"x":-0.149017333984375,"y":-0.11553955078125},{"x":-0.088592529296875,"y":-0.118499755859375},{"x":-0.091583251953125,"y":0.080291748046875},{"x":-0.269866943359375,"y":-0.028350830078125},{"x":-0.093994140625,"y":0.234161376953125},{"x":-0.061798095703125,"y":0.061859130859375},{"x":0.018646240234375,"y":0.23284912109375},{"x":-0.20550537109375,"y":-0.1427764892578125},{"x":-0.39202880859375,"y":0.0208587646484375},{"x":-0.18878173828125,"y":-0.026123046875},{"x":-0.163818359375,"y":-0.16448974609375},{"x":0.007568359375,"y":0.18768310546875},{"x":0.01947021484375,"y":0.006500244140625},{"x":-0.030975341796875,"y":-0.009429931640625},{"x":0.19921875,"y":0.211822509765625},{"x":-0.025146484375,"y":0.1165313720703125},{"x":-0.171478271484375,"y":0.1431427001953125}],"optimisedCameraToObject":{"translation":{"x":-0.06299026169508964,"y":0.11197768862201138,"z":0.23916306896139536},"rotation":{"quaternion":{"W":0.5717275136595683,"X":0.15712756436193404,"Y":-0.308825006540411,"Z":-0.7436838669607198}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":484.7548828125,"y":501.8174133300781},{"x":473.1496887207031,"y":446.285888671875},{"x":461.95703125,"y":392.61138916015625},{"x":451.7514953613281,"y":340.500244140625},{"x":441.5249938964844,"y":290.3243713378906},{"x":431.7090148925781,"y":241.0216827392578},{"x":422.13360595703125,"y":193.94354248046875},{"x":533.637939453125,"y":490.17083740234375},{"x":522.2761840820312,"y":436.22479248046875},{"x":510.2289733886719,"y":383.676025390625},{"x":499.11346435546875,"y":333.1956481933594},{"x":488.76519775390625,"y":284.0886535644531},{"x":478.3763122558594,"y":236.41925048828125},{"x":468.26019287109375,"y":190.12808227539062},{"x":579.957275390625,"y":479.2813720703125},{"x":567.894775390625,"y":426.632568359375},{"x":556.0164184570312,"y":375.7934265136719},{"x":544.6382446289062,"y":326.0128479003906},{"x":533.9013061523438,"y":278.3867492675781},{"x":522.8067626953125,"y":231.18399047851562},{"x":512.52685546875,"y":185.98745727539062},{"x":625.2249145507812,"y":469.0388488769531},{"x":612.7468872070312,"y":417.58502197265625},{"x":600.19384765625,"y":367.6233215332031},{"x":588.2550659179688,"y":319.3221435546875},{"x":577.02392578125,"y":272.89263916015625},{"x":565.8675537109375,"y":226.8433837890625},{"x":555.0606079101562,"y":182.31346130371094},{"x":668.4188842773438,"y":459.2159729003906},{"x":655.1613159179688,"y":408.96746826171875},{"x":642.2734375,"y":360.3509826660156},{"x":630.2301635742188,"y":312.9822082519531},{"x":618.652099609375,"y":267.16326904296875},{"x":606.9793701171875,"y":222.0916290283203},{"x":595.9692993164062,"y":178.84239196777344},{"x":709.8038330078125,"y":449.92645263671875},{"x":696.1832885742188,"y":400.6522521972656},{"x":683.2174682617188,"y":353.06103515625},{"x":670.9382934570312,"y":306.81610107421875},{"x":658.7080078125,"y":261.86737060546875},{"x":647.0568237304688,"y":217.93960571289062},{"x":635.7244262695312,"y":175.2980194091797},{"x":748.939697265625,"y":440.6609802246094},{"x":735.330078125,"y":392.4318542480469},{"x":722.4498901367188,"y":346.1575927734375},{"x":709.5872192382812,"y":300.7352294921875},{"x":697.1796875,"y":256.7798156738281},{"x":685.2068481445312,"y":213.76548767089844},{"x":673.5440673828125,"y":171.968017578125}],"reprojectionErrors":[{"x":-0.72186279296875,"y":-0.164337158203125},{"x":-0.3214111328125,"y":0.029022216796875},{"x":0.021331787109375,"y":0.0804443359375},{"x":-0.285369873046875,"y":0.20037841796875},{"x":-0.249542236328125,"y":-0.061004638671875},{"x":-0.3177490234375,"y":0.2853240966796875},{"x":-0.334259033203125,"y":-0.1806182861328125},{"x":-0.41094970703125,"y":0.0548095703125},{"x":-0.7562255859375,"y":0.100341796875},{"x":-0.052490234375,"y":0.38128662109375},{"x":0.065826416015625,"y":0.149017333984375},{"x":-0.252960205078125,"y":0.025726318359375},{"x":-0.2161865234375,"y":-0.1210479736328125},{"x":-0.151519775390625,"y":-0.2961273193359375},{"x":0.2498779296875,"y":0.034454345703125},{"x":0.158447265625,"y":0.146636962890625},{"x":0.25299072265625,"y":0.005340576171875},{"x":0.20025634765625,"y":0.28924560546875},{"x":-0.1568603515625,"y":-0.165557861328125},{"x":0.16522216796875,"y":0.30810546875},{"x":-0.01995849609375,"y":0.067169189453125},{"x":-0.09954833984375,"y":-0.15069580078125},{"x":-0.17303466796875,"y":0.062103271484375},{"x":0.2034912109375,"y":0.267791748046875},{"x":0.32366943359375,"y":0.230255126953125},{"x":0.078125,"y":-0.325408935546875},{"x":0.08447265625,"y":0.03228759765625},{"x":0.05401611328125,"y":0.1077880859375},{"x":-0.29901123046875,"y":-0.3056640625},{"x":0.05364990234375,"y":-0.06591796875},{"x":0.4150390625,"y":-0.03948974609375},{"x":0.29327392578125,"y":0.094482421875},{"x":0.05181884765625,"y":-0.025970458984375},{"x":0.23565673828125,"y":0.3454437255859375},{"x":0.0732421875,"y":0.0804901123046875},{"x":-0.4871826171875,"y":-0.573638916015625},{"x":-0.085205078125,"y":-0.134735107421875},{"x":0.04248046875,"y":-0.02203369140625},{"x":-0.1527099609375,"y":0.041595458984375},{"x":-0.04876708984375,"y":0.050079345703125},{"x":-0.19061279296875,"y":0.225738525390625},{"x":-0.33203125,"y":0.253326416015625},{"x":-0.10858154296875,"y":-0.4722900390625},{"x":0.00439453125,"y":0.040252685546875},{"x":-0.230712890625,"y":-0.10321044921875},{"x":-0.11822509765625,"y":0.144378662109375},{"x":-0.11138916015625,"y":0.115081787109375},{"x":-0.20428466796875,"y":0.2849578857421875},{"x":-0.28607177734375,"y":0.3310699462890625}],"optimisedCameraToObject":{"translation":{"x":0.014070350287621271,"y":0.12441929445519509,"z":0.302930748193414},"rotation":{"quaternion":{"W":0.63767853747925,"X":0.020020236515058375,"Y":-0.1788726018119348,"Z":-0.7489792155255278}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":412.68487548828125,"y":481.4112854003906},{"x":406.2666320800781,"y":429.9867858886719},{"x":400.16534423828125,"y":381.1138610839844},{"x":393.874755859375,"y":333.1105041503906},{"x":388.11749267578125,"y":287.19244384765625},{"x":382.35546875,"y":241.99374389648438},{"x":376.4107360839844,"y":198.49964904785156},{"x":460.7828369140625,"y":474.321533203125},{"x":452.98626708984375,"y":423.9731750488281},{"x":446.4515380859375,"y":376.1109619140625},{"x":439.87176513671875,"y":328.8658752441406},{"x":433.5757141113281,"y":283.275390625},{"x":427.1769104003906,"y":239.20248413085938},{"x":420.94146728515625,"y":196.71795654296875},{"x":506.9167175292969,"y":467.72088623046875},{"x":498.8377685546875,"y":418.31463623046875},{"x":491.78717041015625,"y":371.0212097167969},{"x":484.0406188964844,"y":324.733154296875},{"x":476.856201171875,"y":280.22467041015625},{"x":470.26068115234375,"y":236.59408569335938},{"x":463.90374755859375,"y":194.7770538330078},{"x":551.721923828125,"y":461.2243957519531},{"x":543.7455444335938,"y":412.8924560546875},{"x":535.0671997070312,"y":365.95611572265625},{"x":527.1407470703125,"y":320.5867004394531},{"x":519.61767578125,"y":276.961669921875},{"x":512.344482421875,"y":233.82083129882812},{"x":505.2715148925781,"y":192.7971649169922},{"x":595.1201171875,"y":454.9154052734375},{"x":585.9742431640625,"y":407.3571472167969},{"x":577.2274780273438,"y":361.4308776855469},{"x":568.900390625,"y":317.13348388671875},{"x":560.9026489257812,"y":273.58355712890625},{"x":553.1318359375,"y":231.2985076904297},{"x":546.0170288085938,"y":190.88011169433594},{"x":637.2794189453125,"y":449.080810546875},{"x":627.4559936523438,"y":401.90289306640625},{"x":618.5140991210938,"y":357.0494689941406},{"x":609.9039306640625,"y":312.96087646484375},{"x":601.1771850585938,"y":270.3092346191406},{"x":592.8782958984375,"y":228.9754638671875},{"x":585.0143432617188,"y":188.89695739746094},{"x":677.9430541992188,"y":442.9905700683594},{"x":667.958984375,"y":397.1317138671875},{"x":658.3965454101562,"y":352.6246032714844},{"x":649.1904296875,"y":309.76470947265625},{"x":640.2280883789062,"y":267.6966552734375},{"x":631.6260986328125,"y":227.0883331298828},{"x":623.255615234375,"y":187.1111297607422}],"reprojectionErrors":[{"x":-0.21661376953125,"y":-0.059326171875},{"x":-0.285003662109375,"y":0.396728515625},{"x":-0.458526611328125,"y":-0.067291259765625},{"x":-0.24139404296875,"y":0.1495361328125},{"x":-0.366119384765625,"y":-0.244384765625},{"x":-0.3038330078125,"y":0.045867919921875},{"x":0.114837646484375,"y":-0.031463623046875},{"x":-0.35223388671875,"y":0.011932373046875},{"x":0.299407958984375,"y":0.36700439453125},{"x":-0.080474853515625,"y":-0.190582275390625},{"x":-0.19622802734375,"y":0.131103515625},{"x":-0.387176513671875,"y":0.2225341796875},{"x":-0.276702880859375,"y":0.1532135009765625},{"x":-0.14019775390625,"y":-0.2110748291015625},{"x":-0.13763427734375,"y":-0.16864013671875},{"x":0.185150146484375,"y":0.181671142578125},{"x":-0.273712158203125,"y":-0.06231689453125},{"x":0.1982421875,"y":0.1336669921875},{"x":0.331817626953125,"y":-0.073211669921875},{"x":0.089752197265625,"y":0.1544189453125},{"x":-0.1873779296875,"y":-0.179473876953125},{"x":-0.123291015625,"y":-0.228546142578125},{"x":-0.47088623046875,"y":-0.0509033203125},{"x":0.1446533203125,"y":0.1976318359375},{"x":0.2572021484375,"y":0.276092529296875},{"x":0.20361328125,"y":-0.058258056640625},{"x":0.12646484375,"y":0.3934173583984375},{"x":0.065185546875,"y":-0.0594329833984375},{"x":-0.151611328125,"y":-0.262786865234375},{"x":0.1424560546875,"y":0.009063720703125},{"x":0.31146240234375,"y":0.066131591796875},{"x":0.322021484375,"y":-0.154815673828125},{"x":0.2525634765625,"y":0.1654052734375},{"x":0.194091796875,"y":0.450897216796875},{"x":-0.29302978515625,"y":0.0448455810546875},{"x":-0.31695556640625,"y":-0.569122314453125},{"x":0.163818359375,"y":0.158447265625},{"x":0.04840087890625,"y":-0.068115234375},{"x":-0.12646484375,"y":0.247711181640625},{"x":0.0751953125,"y":0.3743896484375},{"x":0.09722900390625,"y":0.3751678466796875},{"x":-0.0782470703125,"y":0.2600555419921875},{"x":-0.293701171875,"y":-0.4276123046875},{"x":-0.10888671875,"y":-0.2132568359375},{"x":-0.0504150390625,"y":-0.024688720703125},{"x":-0.0662841796875,"y":-0.2176513671875},{"x":-0.056640625,"y":0.0064697265625},{"x":-0.14984130859375,"y":-0.073516845703125},{"x":-0.228271484375,"y":0.320709228515625}],"optimisedCameraToObject":{"translation":{"x":-0.020924183648255074,"y":0.12182632972271679,"z":0.3321723562292537},"rotation":{"quaternion":{"W":0.6593685096618329,"X":-0.004247625140714078,"Y":-0.1647165844538792,"Z":-0.7335418004127955}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":462.0139465332031,"y":330.98089599609375},{"x":455.95556640625,"y":289.4700012207031},{"x":449.40789794921875,"y":249.09414672851562},{"x":443.4828186035156,"y":209.30186462402344},{"x":437.1956481933594,"y":169.79721069335938},{"x":431.32574462890625,"y":131.13796997070312},{"x":425.7987976074219,"y":92.72907257080078},{"x":503.92034912109375,"y":324.9295654296875},{"x":497.06427001953125,"y":283.6887512207031},{"x":490.71539306640625,"y":243.17332458496094},{"x":483.7601623535156,"y":203.1702423095703},{"x":477.98199462890625,"y":164.0594940185547},{"x":471.8659973144531,"y":125.2406005859375},{"x":465.5221862792969,"y":87.09410095214844},{"x":545.1010131835938,"y":319.05035400390625},{"x":538.0592041015625,"y":278.1039733886719},{"x":531.138427734375,"y":237.35055541992188},{"x":524.6343383789062,"y":197.2819061279297},{"x":517.9017333984375,"y":158.1959991455078},{"x":511.6327819824219,"y":119.32585906982422},{"x":504.9994201660156,"y":81.39358520507812},{"x":587.005615234375,"y":313.0581970214844},{"x":579.7259521484375,"y":271.89044189453125},{"x":572.426025390625,"y":231.55467224121094},{"x":565.0372924804688,"y":191.64120483398438},{"x":558.553955078125,"y":152.28530883789062},{"x":552.1950073242188,"y":113.82444763183594},{"x":545.0242919921875,"y":75.71942901611328},{"x":628.5213623046875,"y":307.1095886230469},{"x":620.8609619140625,"y":265.97967529296875},{"x":613.3915405273438,"y":225.75172424316406},{"x":605.981689453125,"y":185.96237182617188},{"x":598.6099853515625,"y":146.67247009277344},{"x":591.6660766601562,"y":108.05298614501953},{"x":584.882568359375,"y":69.78585815429688},{"x":670.254638671875,"y":301.1470031738281},{"x":662.2259521484375,"y":260.0475769042969},{"x":654.4011840820312,"y":220.06301879882812},{"x":646.97412109375,"y":180.0667724609375},{"x":639.296875,"y":140.9993896484375},{"x":632.06884765625,"y":102.10002136230469},{"x":624.7205810546875,"y":63.970848083496094},{"x":711.6377563476562,"y":295.16766357421875},{"x":703.7738037109375,"y":254.1266632080078},{"x":695.4755249023438,"y":213.8693084716797},{"x":687.2527465820312,"y":173.96481323242188},{"x":679.7658081054688,"y":135.0010528564453},{"x":672.0071411132812,"y":96.21662139892578},{"x":664.3605346679688,"y":58.17169189453125}],"reprojectionErrors":[{"x":-0.09002685546875,"y":0.044769287109375},{"x":-0.290374755859375,"y":0.321136474609375},{"x":0.096435546875,"y":0.1001434326171875},{"x":-0.044189453125,"y":-0.08441162109375},{"x":0.26983642578125,"y":0.0463409423828125},{"x":0.256591796875,"y":-0.081817626953125},{"x":-0.01202392578125,"y":0.11029815673828125},{"x":-0.39801025390625,"y":0.129730224609375},{"x":-0.126953125,"y":0.179412841796875},{"x":-0.259185791015625,"y":0.1406097412109375},{"x":0.3160400390625,"y":0.208740234375},{"x":-0.187530517578125,"y":-0.0132598876953125},{"x":-0.257598876953125,"y":0.058685302734375},{"x":-0.006805419921875,"y":0.02814483642578125},{"x":0.03021240234375,"y":0.03973388671875},{"x":0.1602783203125,"y":-0.162841796875},{"x":0.2794189453125,"y":0.07781982421875},{"x":0.0888671875,"y":0.2522430419921875},{"x":0.23089599609375,"y":0.045440673828125},{"x":0.010498046875,"y":0.2079925537109375},{"x":0.2530517578125,"y":0.00193023681640625},{"x":-0.251220703125,"y":0.059356689453125},{"x":-0.2103271484375,"y":0.119110107421875},{"x":-0.0330810546875,"y":-0.017608642578125},{"x":0.345947265625,"y":0.0412139892578125},{"x":-0.07049560546875,"y":0.143341064453125},{"x":-0.5045166015625,"y":-0.0651092529296875},{"x":-0.022705078125,"y":-0.0607757568359375},{"x":-0.12567138671875,"y":0.031524658203125},{"x":-0.0316162109375,"y":0.09320068359375},{"x":-0.0062255859375,"y":-0.112274169921875},{"x":0.07843017578125,"y":-0.13909912109375},{"x":0.24066162109375,"y":-0.065155029296875},{"x":0.087646484375,"y":-0.07776641845703125},{"x":-0.1163330078125,"y":0.12529754638671875},{"x":-0.1956787109375,"y":0.013214111328125},{"x":-0.0614013671875,"y":0.082916259765625},{"x":-0.00262451171875,"y":-0.3280029296875},{"x":-0.2166748046875,"y":-0.1106109619140625},{"x":-0.05908203125,"y":-0.2224578857421875},{"x":-0.23248291015625,"y":0.08097076416015625},{"x":-0.170654296875,"y":0.181671142578125},{"x":0.1103515625,"y":0.006622314453125},{"x":-0.248779296875,"y":0.055267333984375},{"x":-0.03900146484375,"y":-0.0460968017578125},{"x":0.22613525390625,"y":0.1157379150390625},{"x":-0.11724853515625,"y":-0.0640716552734375},{"x":-0.0650634765625,"y":0.159515380859375},{"x":-0.00433349609375,"y":0.21052932739257812}],"optimisedCameraToObject":{"translation":{"x":0.008752976516492688,"y":0.0520756012394786,"z":0.4092782388669821},"rotation":{"quaternion":{"W":0.6536337131379711,"X":-0.04899189957025912,"Y":-0.04092546885190939,"Z":-0.7541139627571005}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":437.8316955566406,"y":299.3326110839844},{"x":434.7283020019531,"y":259.872802734375},{"x":431.365478515625,"y":220.32431030273438},{"x":428.2330322265625,"y":181.29554748535156},{"x":425.05438232421875,"y":142.4572296142578},{"x":421.763916015625,"y":104.24357604980469},{"x":419.0928649902344,"y":65.95805358886719},{"x":478.2699279785156,"y":295.9954833984375},{"x":474.2554626464844,"y":255.27967834472656},{"x":471.4967346191406,"y":216.12014770507812},{"x":467.8307800292969,"y":176.4092559814453},{"x":464.6946716308594,"y":137.77854919433594},{"x":461.3724060058594,"y":98.76594543457031},{"x":458.1596984863281,"y":60.15728759765625},{"x":518.9759521484375,"y":292.3352355957031},{"x":515.2422485351562,"y":251.7596435546875},{"x":511.7486267089844,"y":211.677490234375},{"x":508.0570068359375,"y":172.14035034179688},{"x":504.7353210449219,"y":132.6052703857422},{"x":501.0166931152344,"y":93.26478576660156},{"x":497.6119689941406,"y":54.27235412597656},{"x":560.8558959960938,"y":288.5968322753906},{"x":556.7958984375,"y":247.4729766845703},{"x":553.0751953125,"y":207.1103515625},{"x":549.0284423828125,"y":166.94204711914062},{"x":545.7173461914062,"y":127.16773223876953},{"x":541.879638671875,"y":87.4098892211914},{"x":538.2125854492188,"y":48.28862762451172},{"x":603.3153076171875,"y":284.6229553222656},{"x":599.2064819335938,"y":243.33621215820312},{"x":595.1773681640625,"y":202.6004638671875},{"x":591.0966796875,"y":162.077880859375},{"x":587.0341186523438,"y":121.8375015258789},{"x":583.3616943359375,"y":81.93097686767578},{"x":579.31005859375,"y":42.29726028442383},{"x":647.1856079101562,"y":281.10443115234375},{"x":642.8778686523438,"y":239.0859832763672},{"x":638.4379272460938,"y":198.03123474121094},{"x":634.3081665039062,"y":156.67486572265625},{"x":630.1488647460938,"y":116.0425033569336},{"x":625.9577026367188,"y":75.99658203125},{"x":691.35400390625,"y":276.695556640625},{"x":687.0432739257812,"y":234.81463623046875},{"x":682.4295654296875,"y":192.90643310546875},{"x":677.9727172851562,"y":151.56935119628906},{"x":673.457763671875,"y":110.65803527832031},{"x":668.834228515625,"y":70.08003997802734}],"reprojectionErrors":[{"x":0.05023193359375,"y":0.246856689453125},{"x":-0.021240234375,"y":-0.111968994140625},{"x":0.194183349609375,"y":-0.0095367431640625},{"x":0.20611572265625,"y":-0.0622100830078125},{"x":0.290557861328125,"y":0.051483154296875},{"x":0.512542724609375,"y":-0.1102294921875},{"x":0.140289306640625,"y":0.1417388916015625},{"x":-0.25555419921875,"y":0.03948974609375},{"x":0.360015869140625,"y":0.551788330078125},{"x":-0.24932861328125,"y":-0.112274169921875},{"x":0.078765869140625,"y":0.146728515625},{"x":-0.093505859375,"y":-0.3107452392578125},{"x":-0.05072021484375,"y":-0.0303802490234375},{"x":-0.089263916015625,"y":0.194366455078125},{"x":-0.0074462890625,"y":0.081268310546875},{"x":0.09466552734375,"y":0.0598297119140625},{"x":-0.008880615234375,"y":-0.0676116943359375},{"x":0.11920166015625,"y":-0.36102294921875},{"x":-0.08978271484375,"y":-0.285675048828125},{"x":0.130340576171875,"y":-0.04207611083984375},{"x":0.068084716796875,"y":0.20851516723632812},{"x":-0.08233642578125,"y":0.1246337890625},{"x":0.1043701171875,"y":0.248931884765625},{"x":-0.0101318359375,"y":0.007232666015625},{"x":0.23870849609375,"y":-0.04217529296875},{"x":-0.21173095703125,"y":-0.107391357421875},{"x":-0.09991455078125,"y":0.180908203125},{"x":-0.123779296875,"y":0.19459152221679688},{"x":0.14495849609375,"y":0.324127197265625},{"x":0.1292724609375,"y":0.199493408203125},{"x":0.0758056640625,"y":-0.07281494140625},{"x":0.114990234375,"y":-0.1638641357421875},{"x":0.17620849609375,"y":-0.15134429931640625},{"x":-0.1134033203125,"y":-0.0953216552734375},{"x":0.01470947265625,"y":0.0570220947265625},{"x":-0.12481689453125,"y":-0.013946533203125},{"x":-0.20294189453125,"y":0.1717071533203125},{"x":-0.10272216796875,"y":-0.194671630859375},{"x":-0.26763916015625,"y":0.1430816650390625},{"x":-0.35894775390625,"y":0.1504364013671875},{"x":-0.37518310546875,"y":-0.04366302490234375},{"x":0.25469970703125,"y":0.45306396484375},{"x":-0.09222412109375,"y":0.069854736328125},{"x":-0.08575439453125,"y":0.1342010498046875},{"x":-0.1868896484375,"y":0.038299560546875},{"x":-0.181640625,"y":-0.08162689208984375},{"x":-0.0206298828125,"y":-0.1420135498046875}],"optimisedCameraToObject":{"translation":{"x":-0.00649965680817032,"y":0.032234337227109604,"z":0.433236415945914},"rotation":{"quaternion":{"W":0.6738732012823913,"X":-0.08779367919998371,"Y":0.036153567128207525,"Z":-0.7327210233573609}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":395.684326171875,"y":336.1977844238281},{"x":397.1968078613281,"y":296.44244384765625},{"x":399.40557861328125,"y":257.1900329589844},{"x":400.7370300292969,"y":217.424072265625},{"x":402.74981689453125,"y":177.88430786132812},{"x":404.5721740722656,"y":138.21475219726562},{"x":406.26153564453125,"y":98.46859741210938},{"x":434.249755859375,"y":338.4228210449219},{"x":436.2884521484375,"y":298.12841796875},{"x":437.83599853515625,"y":258.0708312988281},{"x":439.9877624511719,"y":218.1559295654297},{"x":441.5372314453125,"y":177.64044189453125},{"x":443.3737487792969,"y":137.373046875},{"x":445.1820068359375,"y":97.07520294189453},{"x":473.57586669921875,"y":340.520263671875},{"x":475.6824035644531,"y":300.4468688964844},{"x":477.68212890625,"y":259.1902160644531},{"x":479.3145446777344,"y":218.2369384765625},{"x":481.4943542480469,"y":177.40699768066406},{"x":482.9393615722656,"y":136.73367309570312},{"x":485.29949951171875,"y":95.44046020507812},{"x":515.100341796875,"y":343.95733642578125},{"x":517.0298461914062,"y":301.3711242675781},{"x":519.1610107421875,"y":260.1547546386719},{"x":520.4619140625,"y":218.57571411132812},{"x":522.71533203125,"y":177.5193328857422},{"x":524.4631958007812,"y":135.35162353515625},{"x":526.8110961914062,"y":93.819580078125},{"x":557.794677734375,"y":345.9543151855469},{"x":559.6544799804688,"y":304.0678405761719},{"x":561.40380859375,"y":261.7607116699219},{"x":563.6455688476562,"y":219.14991760253906},{"x":565.271728515625,"y":176.79200744628906},{"x":567.08984375,"y":134.7111358642578},{"x":569.2051391601562,"y":92.37162780761719},{"x":602.409912109375,"y":349.113037109375},{"x":603.8955078125,"y":305.5611572265625},{"x":605.6168823242188,"y":262.62823486328125},{"x":607.3524169921875,"y":219.4876251220703},{"x":609.3762817382812,"y":176.929443359375},{"x":611.3655395507812,"y":133.54202270507812},{"x":613.2556762695312,"y":91.00001525878906},{"x":648.1327514648438,"y":351.99884033203125},{"x":649.5233154296875,"y":307.81256103515625},{"x":651.6337890625,"y":264.01007080078125},{"x":653.2891845703125,"y":220.2771453857422},{"x":655.1876831054688,"y":176.23899841308594},{"x":657.6190795898438,"y":132.27880859375},{"x":659.3292846679688,"y":88.42567443847656}],"reprojectionErrors":[{"x":-0.046417236328125,"y":0.18963623046875},{"x":0.2933349609375,"y":0.18756103515625},{"x":-0.070556640625,"y":-0.263580322265625},{"x":0.4356689453125,"y":-0.1501312255859375},{"x":0.253509521484375,"y":-0.214691162109375},{"x":0.254852294921875,"y":-0.1040496826171875},{"x":0.382415771484375,"y":0.1257781982421875},{"x":-0.02984619140625,"y":0.355682373046875},{"x":-0.2132568359375,"y":0.24237060546875},{"x":0.087890625,"y":-0.05206298828125},{"x":-0.2215576171875,"y":-0.4364471435546875},{"x":0.064971923828125,"y":-0.1703948974609375},{"x":0.058319091796875,"y":-0.1055145263671875},{"x":0.07391357421875,"y":0.03385162353515625},{"x":0.502838134765625,"y":0.7296142578125},{"x":0.253875732421875,"y":-0.277801513671875},{"x":0.105987548828125,"y":-0.044403076171875},{"x":0.31982421875,"y":-0.059783935546875},{"x":-0.019195556640625,"y":-0.14697265625},{"x":0.37127685546875,"y":-0.34222412109375},{"x":-0.158538818359375,"y":0.1279754638671875},{"x":0.1822509765625,"y":-0.15142822265625},{"x":0.11175537109375,"y":0.656768798828125},{"x":-0.16522216796875,"y":0.154754638671875},{"x":0.38336181640625,"y":0.0718994140625},{"x":-0.025146484375,"y":-0.48028564453125},{"x":0.0675048828125,"y":0.129119873046875},{"x":-0.44415283203125,"y":0.1500091552734375},{"x":0.11016845703125,"y":0.496795654296875},{"x":0.10986328125,"y":-0.11724853515625},{"x":0.2161865234375,"y":-0.248870849609375},{"x":-0.1737060546875,"y":-0.01837158203125},{"x":0.0484619140625,"y":0.0145111083984375},{"x":0.0751953125,"y":-0.1776123046875},{"x":-0.19854736328125,"y":-0.062255859375},{"x":-0.3858642578125,"y":0.07745361328125},{"x":-0.01251220703125,"y":0.379547119140625},{"x":0.12225341796875,"y":0.126678466796875},{"x":0.2401123046875,"y":0.14208984375},{"x":0.067138671875,"y":-0.3676605224609375},{"x":-0.07366943359375,"y":0.005767822265625},{"x":-0.11761474609375,"y":-0.41559600830078125},{"x":-0.40789794921875,"y":0.030517578125},{"x":0.05877685546875,"y":0.189453125},{"x":-0.19622802734375,"y":0.030975341796875},{"x":0.0023193359375,"y":-0.13421630859375},{"x":-0.043701171875,"y":0.0652008056640625},{"x":-0.62396240234375,"y":0.2425994873046875},{"x":-0.484130859375,"y":0.3654327392578125}],"optimisedCameraToObject":{"translation":{"x":-0.03587042973479231,"y":0.05259333743163324,"z":0.4422198039842793},"rotation":{"quaternion":{"W":0.7155858041475371,"X":-0.1047430623683691,"Y":0.09242382391095598,"Z":-0.6844148482915132}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":380.54949951171875,"y":377.2850341796875},{"x":384.03192138671875,"y":338.6522521972656},{"x":388.32415771484375,"y":300.2995300292969},{"x":391.40289306640625,"y":261.0733337402344},{"x":395.24322509765625,"y":222.80470275878906},{"x":399.0485534667969,"y":184.6976776123047},{"x":402.3706970214844,"y":146.76731872558594},{"x":415.6609802246094,"y":382.546630859375},{"x":419.74951171875,"y":342.02313232421875},{"x":422.9712219238281,"y":302.5527648925781},{"x":427.30859375,"y":262.8040771484375},{"x":430.6711730957031,"y":223.48556518554688},{"x":434.05767822265625,"y":184.19577026367188},{"x":437.8306579589844,"y":145.45858764648438},{"x":452.7651062011719,"y":386.9320983886719},{"x":456.6573181152344,"y":345.6403503417969},{"x":460.46246337890625,"y":305.0274963378906},{"x":463.91680908203125,"y":264.25933837890625},{"x":467.3416442871094,"y":224.16355895996094},{"x":471.07269287109375,"y":184.00399780273438},{"x":474.7296142578125,"y":144.16114807128906},{"x":492.06170654296875,"y":392.2479553222656},{"x":495.5417175292969,"y":349.2261657714844},{"x":499.8452453613281,"y":307.2464599609375},{"x":503.1149597167969,"y":266.1851806640625},{"x":506.6823425292969,"y":224.88275146484375},{"x":510.1293640136719,"y":183.42703247070312},{"x":513.8094482421875,"y":142.63717651367188},{"x":533.4989624023438,"y":397.8182067871094},{"x":536.9718017578125,"y":354.03277587890625},{"x":540.742919921875,"y":310.9837341308594},{"x":544.2440185546875,"y":267.76446533203125},{"x":547.7286376953125,"y":225.5476837158203},{"x":551.2493286132812,"y":182.986328125},{"x":555.066162109375,"y":141.12498474121094},{"x":577.4182739257812,"y":403.6539001464844},{"x":581.18896484375,"y":358.6499328613281},{"x":584.4886474609375,"y":314.233154296875},{"x":587.9926147460938,"y":269.9983215332031},{"x":590.9603271484375,"y":226.77833557128906},{"x":595.14306640625,"y":182.64381408691406},{"x":598.5363159179688,"y":139.23106384277344},{"x":624.2034301757812,"y":409.9255676269531},{"x":627.4891967773438,"y":363.275146484375},{"x":630.8190307617188,"y":317.34814453125},{"x":634.1090698242188,"y":272.1258544921875},{"x":637.6980590820312,"y":227.03536987304688},{"x":640.815673828125,"y":182.20172119140625},{"x":644.38525390625,"y":137.4024200439453}],"reprojectionErrors":[{"x":-0.06939697265625,"y":0.5389404296875},{"x":0.217315673828125,"y":0.026611328125},{"x":-0.337921142578125,"y":-0.509765625},{"x":0.288726806640625,"y":0.078460693359375},{"x":0.12274169921875,"y":-0.0446319580078125},{"x":-0.038726806640625,"y":-0.08782958984375},{"x":0.252960205078125,"y":-0.0708770751953125},{"x":0.179840087890625,"y":-0.12835693359375},{"x":-0.16302490234375,"y":0.236083984375},{"x":0.328887939453125,"y":-0.183197021484375},{"x":-0.326324462890625,"y":-0.059967041015625},{"x":-0.03765869140625,"y":-0.1078948974609375},{"x":0.196685791015625,"y":0.06939697265625},{"x":0.01470947265625,"y":-0.0569305419921875},{"x":0.286102294921875,"y":0.322509765625},{"x":0.108551025390625,"y":0.386199951171875},{"x":-0.0137939453125,"y":0.054901123046875},{"x":0.183441162109375,"y":0.1572265625},{"x":0.37945556640625,"y":-0.1400146484375},{"x":0.239105224609375,"y":-0.1060791015625},{"x":0.143280029296875,"y":-0.1267547607421875},{"x":0.2025146484375,"y":0.10504150390625},{"x":0.397430419921875,"y":0.770111083984375},{"x":-0.262664794921875,"y":0.6927490234375},{"x":0.080108642578125,"y":-0.009429931640625},{"x":0.0948486328125,"y":-0.1827239990234375},{"x":0.200164794921875,"y":0.0792388916015625},{"x":0.04315185546875,"y":-0.048370361328125},{"x":0.15118408203125,"y":-0.08251953125},{"x":0.30352783203125,"y":0.15277099609375},{"x":0.12652587890625,"y":-0.0316162109375},{"x":0.1890869140625,"y":0.26446533203125},{"x":0.23822021484375,"y":-0.1380157470703125},{"x":0.22198486328125,"y":0.101837158203125},{"x":-0.11920166015625,"y":-0.0666351318359375},{"x":-0.01904296875,"y":-0.226318359375},{"x":-0.2259521484375,"y":-0.036407470703125},{"x":0.0076904296875,"y":-0.098419189453125},{"x":0.00726318359375,"y":-0.0140380859375},{"x":0.5137939453125,"y":-0.62298583984375},{"x":-0.223388671875,"y":-0.0024566650390625},{"x":-0.19915771484375,"y":0.2047119140625},{"x":-0.47894287109375,"y":-0.468994140625},{"x":-0.27581787109375,"y":0.0264892578125},{"x":-0.1463623046875,"y":0.154083251953125},{"x":-0.00616455078125,"y":-0.074981689453125},{"x":-0.19329833984375,"y":-0.0951080322265625},{"x":0.0631103515625,"y":-0.0384063720703125},{"x":-0.15972900390625,"y":0.3105621337890625}],"optimisedCameraToObject":{"translation":{"x":-0.0454814246617651,"y":0.0792390766317016,"z":0.4514262702872477},"rotation":{"quaternion":{"W":0.7161716730190356,"X":-0.183864132748019,"Y":0.12992561076625342,"Z":-0.6606144496761711}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":100.627197265625,"y":512.48291015625},{"x":113.74388885498047,"y":469.9773254394531},{"x":125.83038330078125,"y":428.80316162109375},{"x":137.96168518066406,"y":388.732421875},{"x":149.5819549560547,"y":349.9420471191406},{"x":160.49606323242188,"y":312.1221008300781},{"x":171.7385711669922,"y":275.89080810546875},{"x":138.58291625976562,"y":521.2918701171875},{"x":151.0233917236328,"y":477.9831848144531},{"x":163.0851593017578,"y":436.23443603515625},{"x":174.63441467285156,"y":395.4124450683594},{"x":185.8813018798828,"y":356.2745666503906},{"x":196.48313903808594,"y":318.2669372558594},{"x":207.07965087890625,"y":281.2242126464844},{"x":176.9467315673828,"y":529.9638061523438},{"x":188.99118041992188,"y":486.2641296386719},{"x":200.38059997558594,"y":443.9945068359375},{"x":211.52049255371094,"y":402.87725830078125},{"x":222.35748291015625,"y":362.9833679199219},{"x":232.73672485351562,"y":324.3127136230469},{"x":242.82656860351562,"y":287.06268310546875},{"x":216.4814453125,"y":539.5264282226562},{"x":228.02984619140625,"y":495.0830078125},{"x":238.98377990722656,"y":451.897705078125},{"x":249.53469848632812,"y":410.0996398925781},{"x":260.12298583984375,"y":369.8481750488281},{"x":269.95037841796875,"y":330.9191589355469},{"x":279.345703125,"y":292.55029296875},{"x":267.5289001464844,"y":503.2486267089844},{"x":278.1286926269531,"y":459.5924377441406},{"x":287.9828796386719,"y":417.46734619140625},{"x":298.14215087890625,"y":376.72869873046875},{"x":307.639892578125,"y":336.9919738769531},{"x":316.83642578125,"y":298.6980285644531},{"x":308.4164733886719,"y":512.12255859375},{"x":318.3217468261719,"y":468.1593933105469},{"x":327.9200439453125,"y":425.2945251464844},{"x":336.84356689453125,"y":383.8410949707031},{"x":346.1623840332031,"y":343.42901611328125},{"x":354.9245300292969,"y":304.6334228515625},{"x":349.6992492675781,"y":521.2599487304688},{"x":359.12701416015625,"y":476.79693603515625},{"x":367.8465881347656,"y":433.0384521484375},{"x":376.8867492675781,"y":391.0769348144531},{"x":385.3934631347656,"y":350.2148132324219},{"x":393.693359375,"y":311.0393981933594}],"reprojectionErrors":[{"x":0.36865997314453125,"y":-0.19378662109375},{"x":0.01593780517578125,"y":-0.1524658203125},{"x":0.2921295166015625,"y":-0.138641357421875},{"x":0.141265869140625,"y":0.0137939453125},{"x":0.137054443359375,"y":0.06976318359375},{"x":0.49139404296875,"y":0.284698486328125},{"x":0.1854705810546875,"y":-0.010894775390625},{"x":0.0699920654296875,"y":-0.27276611328125},{"x":-0.059112548828125,"y":-0.038116455078125},{"x":-0.20025634765625,"y":-0.02606201171875},{"x":-0.200897216796875,"y":0.332427978515625},{"x":-0.2536163330078125,"y":0.21978759765625},{"x":7.171630859375E-4,"y":0.13348388671875},{"x":-0.0621337890625,"y":0.185882568359375},{"x":0.2134552001953125,"y":-0.01434326171875},{"x":0.00439453125,"y":-0.01666259765625},{"x":0.0711212158203125,"y":-0.076934814453125},{"x":0.026519775390625,"y":0.0159912109375},{"x":-0.058837890625,"y":0.1287841796875},{"x":-0.01397705078125,"y":0.203216552734375},{"x":0.0079193115234375,"y":-0.01300048828125},{"x":0.069305419921875,"y":-0.4384765625},{"x":-0.14447021484375,"y":-0.343994140625},{"x":-0.130462646484375,"y":-0.099334716796875},{"x":-0.0621337890625,"y":0.097320556640625},{"x":-0.36309814453125,"y":0.022064208984375},{"x":-0.219329833984375,"y":-0.16143798828125},{"x":0.055084228515625,"y":0.252288818359375},{"x":0.138092041015625,"y":0.178466796875},{"x":-0.007049560546875,"y":0.264862060546875},{"x":0.257904052734375,"y":0.194549560546875},{"x":-0.101348876953125,"y":0.045135498046875},{"x":-0.102935791015625,"y":0.138458251953125},{"x":-0.092864990234375,"y":-0.02508544921875},{"x":-0.04107666015625,"y":0.19677734375},{"x":-0.031585693359375,"y":-0.05810546875},{"x":-0.036224365234375,"y":-3.96728515625E-4},{"x":0.32861328125,"y":-0.012725830078125},{"x":0.00762939453125,"y":0.2099609375},{"x":-0.033355712890625,"y":0.03167724609375},{"x":0.3482666015625,"y":0.1639404296875},{"x":0.267181396484375,"y":-0.259368896484375},{"x":0.588836669921875,"y":0.061737060546875},{"x":0.29962158203125,"y":-0.03729248046875},{"x":0.267791748046875,"y":0.073638916015625},{"x":0.1800537109375,"y":-0.255889892578125}],"optimisedCameraToObject":{"translation":{"x":-0.21809177682818243,"y":0.15386097795423498,"z":0.4119956494673318},"rotation":{"quaternion":{"W":0.756263881302583,"X":-0.1548848734523167,"Y":-0.04045674166084095,"Z":-0.6343806978991404}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":159.6721954345703,"y":504.563720703125},{"x":169.47000122070312,"y":464.2469787597656},{"x":179.44076538085938,"y":425.63104248046875},{"x":188.33302307128906,"y":388.8910217285156},{"x":197.3285369873047,"y":353.2066345214844},{"x":205.84747314453125,"y":319.01934814453125},{"x":214.0684051513672,"y":286.01409912109375},{"x":190.45469665527344,"y":508.0657958984375},{"x":200.23629760742188,"y":466.9756774902344},{"x":209.2681427001953,"y":427.58355712890625},{"x":218.29531860351562,"y":389.4523010253906},{"x":226.8802032470703,"y":353.2420349121094},{"x":234.9364471435547,"y":318.477294921875},{"x":242.21730041503906,"y":285.03857421875},{"x":222.90699768066406,"y":511.98468017578125},{"x":232.24879455566406,"y":469.6133117675781},{"x":240.74497985839844,"y":429.1042175292969},{"x":249.02352905273438,"y":390.5260314941406},{"x":257.154541015625,"y":353.3603820800781},{"x":264.6189880371094,"y":318.02044677734375},{"x":272.1707763671875,"y":283.64605712890625},{"x":256.7322692871094,"y":516.1222534179688},{"x":265.6434326171875,"y":472.4615478515625},{"x":273.0390319824219,"y":431.68310546875},{"x":281.58160400390625,"y":391.4876708984375},{"x":288.9893798828125,"y":353.6029357910156},{"x":296.23828125,"y":316.9132385253906},{"x":302.9258117675781,"y":282.27801513671875},{"x":292.3006286621094,"y":520.12060546875},{"x":300.14935302734375,"y":475.57666015625},{"x":307.95086669921875,"y":433.0826110839844},{"x":315.31866455078125,"y":392.50299072265625},{"x":322.20086669921875,"y":353.6576232910156},{"x":328.9137878417969,"y":316.19427490234375},{"x":335.24481201171875,"y":280.6071472167969},{"x":329.8935852050781,"y":524.8690795898438},{"x":337.20123291015625,"y":478.8597106933594},{"x":344.0658264160156,"y":435.3133544921875},{"x":350.72393798828125,"y":393.17877197265625},{"x":357.30755615234375,"y":353.824951171875},{"x":363.4542236328125,"y":315.65203857421875},{"x":369.1438903808594,"y":279.0775146484375},{"x":368.89910888671875,"y":528.90478515625},{"x":375.8826599121094,"y":482.316162109375},{"x":381.8960876464844,"y":437.64544677734375},{"x":387.92138671875,"y":394.85693359375},{"x":393.430908203125,"y":353.82208251953125},{"x":398.8918762207031,"y":314.8960876464844},{"x":404.0500183105469,"y":277.395263671875}],"reprojectionErrors":[{"x":0.3941192626953125,"y":-0.476287841796875},{"x":0.5338287353515625,"y":-0.1004638671875},{"x":0.094970703125,"y":0.159332275390625},{"x":0.3532562255859375,"y":0.03326416015625},{"x":0.149261474609375,"y":0.2542724609375},{"x":0.08343505859375,"y":0.30023193359375},{"x":-0.003692626953125,"y":0.41162109375},{"x":0.3051605224609375,"y":-0.27227783203125},{"x":0.05804443359375,"y":-0.1414794921875},{"x":0.162689208984375,"y":-0.045806884765625},{"x":-0.1016693115234375,"y":0.3502197265625},{"x":-0.275054931640625,"y":0.292999267578125},{"x":-0.250518798828125,"y":0.17181396484375},{"x":0.2377471923828125,"y":0.026641845703125},{"x":0.047515869140625,"y":-0.304534912109375},{"x":-0.2139739990234375,"y":0.03509521484375},{"x":-0.0177154541015625,"y":0.25933837890625},{"x":0.0325469970703125,"y":0.190399169921875},{"x":-0.111053466796875,"y":0.246368408203125},{"x":0.0909423828125,"y":-0.078094482421875},{"x":-0.096435546875,"y":-0.00787353515625},{"x":0.034576416015625,"y":-0.36083984375},{"x":-0.3079833984375,"y":0.13720703125},{"x":0.490264892578125,"y":-0.40948486328125},{"x":-0.209320068359375,"y":0.180908203125},{"x":-0.10296630859375,"y":0.072967529296875},{"x":-0.146484375,"y":0.283477783203125},{"x":0.081207275390625,"y":-0.137969970703125},{"x":0.025115966796875,"y":-0.06787109375},{"x":0.168487548828125,"y":0.119171142578125},{"x":8.85009765625E-4,"y":0.19183349609375},{"x":-0.067779541015625,"y":0.158905029296875},{"x":0.035858154296875,"y":0.08465576171875},{"x":0.01507568359375,"y":0.215179443359375},{"x":0.100555419921875,"y":-0.041290283203125},{"x":-0.119384765625,"y":-0.29766845703125},{"x":-0.084716796875,"y":0.091705322265625},{"x":0.05560302734375,"y":0.059722900390625},{"x":0.087554931640625,"y":0.520721435546875},{"x":-0.10015869140625,"y":-0.01922607421875},{"x":-0.126251220703125,"y":-0.074554443359375},{"x":0.046661376953125,"y":-0.1673583984375},{"x":0.37213134765625,"y":0.431640625},{"x":-0.001800537109375,"y":0.06231689453125},{"x":0.282684326171875,"y":-0.06805419921875},{"x":0.26495361328125,"y":-0.072052001953125},{"x":0.492156982421875,"y":0.04388427734375},{"x":0.514892578125,"y":-0.198577880859375},{"x":0.60369873046875,"y":-0.228363037109375}],"optimisedCameraToObject":{"translation":{"x":-0.18890790971263002,"y":0.16124954893029037,"z":0.4418877903736808},"rotation":{"quaternion":{"W":0.6945063746670967,"X":-0.28319207152817016,"Y":0.011552546083988409,"Z":-0.6613090690814146}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":57.27147674560547,"y":488.0624694824219},{"x":59.157958984375,"y":445.825927734375},{"x":60.74742889404297,"y":403.8450012207031},{"x":62.34703826904297,"y":361.5035095214844},{"x":64.34295654296875,"y":319.6330261230469},{"x":65.80378723144531,"y":278.1210021972656},{"x":67.31890106201172,"y":236.57785034179688},{"x":96.68072509765625,"y":490.4915771484375},{"x":98.26736450195312,"y":447.7634582519531},{"x":99.84481811523438,"y":405.572021484375},{"x":101.64117431640625,"y":363.5294494628906},{"x":103.58287811279297,"y":321.3747863769531},{"x":104.85736846923828,"y":279.1960144042969},{"x":106.5478515625,"y":237.20364379882812},{"x":136.60523986816406,"y":493.0823974609375},{"x":138.22412109375,"y":450.07879638671875},{"x":140.03948974609375,"y":407.4130859375},{"x":141.85948181152344,"y":365.0420227050781},{"x":143.39369201660156,"y":322.58392333984375},{"x":144.79190063476562,"y":279.930908203125},{"x":146.48060607910156,"y":237.7360076904297},{"x":177.24420166015625,"y":495.8937683105469},{"x":178.75274658203125,"y":452.5513916015625},{"x":180.33438110351562,"y":409.3316650390625},{"x":181.6788330078125,"y":366.79205322265625},{"x":183.2374267578125,"y":323.4889221191406},{"x":184.7845001220703,"y":281.3111267089844},{"x":186.39471435546875,"y":238.4470672607422},{"x":218.11769104003906,"y":498.5357666015625},{"x":220.13320922851562,"y":454.47052001953125},{"x":221.7132568359375,"y":411.4927673339844},{"x":223.23785400390625,"y":367.9117736816406},{"x":224.74742126464844,"y":325.12335205078125},{"x":226.2710418701172,"y":282.1729431152344},{"x":227.45860290527344,"y":239.4380340576172},{"x":260.1639404296875,"y":501.0629577636719},{"x":261.6707763671875,"y":456.83831787109375},{"x":263.0765380859375,"y":413.0647277832031},{"x":264.5279235839844,"y":369.8215026855469},{"x":266.2131042480469,"y":326.4790954589844},{"x":267.7347717285156,"y":283.0061340332031},{"x":268.63800048828125,"y":240.01385498046875}],"reprojectionErrors":[{"x":0.10436630249023438,"y":-0.093536376953125},{"x":-0.039089202880859375,"y":-0.07440185546875},{"x":0.09823226928710938,"y":-0.176666259765625},{"x":0.20938491821289062,"y":0.2120361328125},{"x":-0.0915985107421875,"y":0.25640869140625},{"x":0.12686920166015625,"y":0.06536865234375},{"x":0.2756195068359375,"y":0.0247955322265625},{"x":0.09706878662109375,"y":-0.022308349609375},{"x":0.20412445068359375,"y":0.175384521484375},{"x":0.30516815185546875,"y":-0.027435302734375},{"x":0.1722869873046875,"y":-0.2467041015625},{"x":-0.12075042724609375,"y":-0.225341796875},{"x":0.23879241943359375,"y":-0.05499267578125},{"x":0.16790008544921875,"y":0.05010986328125},{"x":0.145538330078125,"y":-0.0701904296875},{"x":0.1694488525390625,"y":0.08392333984375},{"x":-0.0172882080078125,"y":0.03839111328125},{"x":-0.22259521484375,"y":-0.167388916015625},{"x":-0.1558990478515625,"y":-0.155609130859375},{"x":0.0332183837890625,"y":0.177825927734375},{"x":-0.0815887451171875,"y":0.1761016845703125},{"x":0.0671844482421875,"y":-0.2947998046875},{"x":0.14886474609375,"y":-0.127166748046875},{"x":0.1444091796875,"y":0.058197021484375},{"x":0.3642578125,"y":-0.300079345703125},{"x":0.3572845458984375,"y":0.237640380859375},{"x":0.34930419921875,"y":-0.221282958984375},{"x":0.2658233642578125,"y":0.1309051513671875},{"x":0.3590850830078125,"y":-0.30499267578125},{"x":-0.1204833984375,"y":0.25390625},{"x":-0.1764984130859375,"y":-0.132110595703125},{"x":-0.188812255859375,"y":0.223663330078125},{"x":-0.1976776123046875,"y":-0.078582763671875},{"x":-0.2320098876953125,"y":-0.088165283203125},{"x":0.0584869384765625,"y":-0.186492919921875},{"x":0.100860595703125,"y":-0.154022216796875},{"x":0.07391357421875,"y":0.226104736328125},{"x":0.13726806640625,"y":0.300018310546875},{"x":0.144439697265625,"y":-0.015716552734375},{"x":-0.092620849609375,"y":-0.095611572265625},{"x":-0.17645263671875,"y":0.0877685546875},{"x":0.34808349609375,"y":-0.0807647705078125}],"optimisedCameraToObject":{"translation":{"x":-0.2654578887537667,"y":0.14254284832387834,"z":0.41797373587380215},"rotation":{"quaternion":{"W":0.715190757974502,"X":-0.05123942955878353,"Y":0.03265824369797332,"Z":-0.6962830887540724}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":197.0192108154297,"y":459.97674560546875},{"x":193.77171325683594,"y":426.9280700683594},{"x":190.14236450195312,"y":392.2505187988281},{"x":186.93414306640625,"y":356.01068115234375},{"x":183.01612854003906,"y":318.16851806640625},{"x":178.9229736328125,"y":277.6587829589844},{"x":174.8429718017578,"y":235.32180786132812},{"x":237.63330078125,"y":459.7091369628906},{"x":235.70652770996094,"y":426.8940124511719},{"x":233.0524444580078,"y":392.7461853027344},{"x":230.78956604003906,"y":356.6147155761719},{"x":228.19430541992188,"y":318.8173522949219},{"x":225.34506225585938,"y":278.6951904296875},{"x":222.280517578125,"y":236.41818237304688},{"x":277.9340515136719,"y":459.7793273925781},{"x":276.28369140625,"y":426.9144592285156},{"x":275.0760803222656,"y":392.8156433105469},{"x":273.6636962890625,"y":357.0073547363281},{"x":271.9820251464844,"y":319.0929260253906},{"x":270.4635009765625,"y":279.8805847167969},{"x":269.1711120605469,"y":237.75572204589844},{"x":317.4831848144531,"y":459.5060119628906},{"x":317.19476318359375,"y":427.0437927246094},{"x":316.9170837402344,"y":393.0534362792969},{"x":316.6590881347656,"y":357.2911682128906},{"x":316.3311767578125,"y":319.9710388183594},{"x":315.8879089355469,"y":280.60247802734375},{"x":315.1629638671875,"y":239.1409149169922},{"x":356.75030517578125,"y":459.48822021484375},{"x":357.23614501953125,"y":427.1272888183594},{"x":357.9862976074219,"y":393.44580078125},{"x":358.6783447265625,"y":358.0254821777344},{"x":359.40472412109375,"y":320.7746276855469},{"x":360.1905212402344,"y":281.31146240234375},{"x":360.9068298339844,"y":239.87416076660156},{"x":395.6778259277344,"y":459.5659484863281},{"x":397.15582275390625,"y":427.2886047363281},{"x":398.9761657714844,"y":393.76239013671875},{"x":400.84912109375,"y":358.37359619140625},{"x":402.4006652832031,"y":321.3421936035156},{"x":404.7115478515625,"y":282.24554443359375},{"x":406.0309753417969,"y":241.66102600097656},{"x":433.985595703125,"y":459.57940673828125},{"x":436.8075866699219,"y":427.5600280761719},{"x":439.4069519042969,"y":394.20794677734375},{"x":441.92303466796875,"y":358.9388427734375},{"x":444.31195068359375,"y":321.8750915527344},{"x":448.0299072265625,"y":283.11968994140625},{"x":451.19671630859375,"y":242.19981384277344}],"reprojectionErrors":[{"x":0.383697509765625,"y":-0.419403076171875},{"x":0.3570404052734375,"y":-0.134185791015625},{"x":0.54180908203125,"y":0.122894287109375},{"x":0.1214141845703125,"y":0.15301513671875},{"x":0.211700439453125,"y":-0.150482177734375},{"x":0.26123046875,"y":0.114501953125},{"x":0.0630035400390625,"y":-0.0744476318359375},{"x":0.1271820068359375,"y":-0.224151611328125},{"x":-0.2083892822265625,"y":-0.017059326171875},{"x":0.06591796875,"y":-0.11822509765625},{"x":-0.177734375,"y":-0.007049560546875},{"x":-0.22607421875,"y":-0.145751953125},{"x":-0.1690216064453125,"y":-0.036041259765625},{"x":-0.05804443359375,"y":-0.0269927978515625},{"x":-0.194488525390625,"y":-0.353363037109375},{"x":0.18634033203125,"y":0.056915283203125},{"x":0.058502197265625,"y":0.07586669921875},{"x":0.0643310546875,"y":0.05059814453125},{"x":0.262542724609375,"y":0.2354736328125},{"x":0.214324951171875,"y":-0.33587646484375},{"x":-0.15045166015625,"y":-0.225128173828125},{"x":-0.1346435546875,"y":-0.1258544921875},{"x":-0.14141845703125,"y":0.033172607421875},{"x":-0.174713134765625,"y":0.110504150390625},{"x":-0.244781494140625,"y":0.223358154296875},{"x":-0.26336669921875,"y":0.01739501953125},{"x":-0.18658447265625,"y":-0.1724853515625},{"x":0.15020751953125,"y":-0.4751739501953125},{"x":-0.154754638671875,"y":-0.140899658203125},{"x":0.02069091796875,"y":0.066314697265625},{"x":-0.0352783203125,"y":-6.103515625E-4},{"x":0.002288818359375,"y":-0.048187255859375},{"x":0.043853759765625,"y":-0.122894287109375},{"x":0.06744384765625,"y":0.003692626953125},{"x":0.20550537109375,"y":-0.0773773193359375},{"x":-0.18927001953125,"y":-0.2386474609375},{"x":-0.06689453125,"y":0.032501220703125},{"x":-0.206634521484375,"y":-0.02728271484375},{"x":-0.312469482421875,"y":0.0726318359375},{"x":-0.00347900390625,"y":-0.02392578125},{"x":-0.35272216796875,"y":-0.04534912109375},{"x":0.399078369140625,"y":-0.7371063232421875},{"x":0.049713134765625,"y":-0.259490966796875},{"x":-0.249725341796875,"y":-0.10064697265625},{"x":-0.2001953125,"y":-0.17431640625},{"x":0.0687255859375,"y":-0.017578125},{"x":0.611785888671875,"y":0.11297607421875},{"x":-0.01519775390625,"y":-0.034423828125},{"x":0.081268310546875,"y":-0.1525115966796875}],"optimisedCameraToObject":{"translation":{"x":-0.1638203701330219,"y":0.12981318495204788,"z":0.44536717370473994},"rotation":{"quaternion":{"W":0.7025158319005481,"X":0.17779604942108784,"Y":0.1252839834395075,"Z":-0.6776164064076844}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img11.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":339.9504089355469,"y":260.95489501953125},{"x":340.2064514160156,"y":234.3365478515625},{"x":340.8134765625,"y":206.11473083496094},{"x":341.31658935546875,"y":174.08148193359375},{"x":342.11767578125,"y":139.19009399414062},{"x":342.3880310058594,"y":99.56565856933594},{"x":343.0404357910156,"y":55.37980651855469},{"x":378.26263427734375,"y":257.9170837402344},{"x":380.614990234375,"y":231.68191528320312},{"x":383.0124816894531,"y":203.04998779296875},{"x":385.78253173828125,"y":171.45018005371094},{"x":388.2790832519531,"y":136.92758178710938},{"x":391.80169677734375,"y":97.56710815429688},{"x":395.2097473144531,"y":54.167354583740234},{"x":415.8338317871094,"y":254.49884033203125},{"x":419.4979248046875,"y":228.5644989013672},{"x":423.76629638671875,"y":200.22732543945312},{"x":428.205322265625,"y":169.17715454101562},{"x":433.7202453613281,"y":134.42433166503906},{"x":439.82330322265625,"y":95.97762298583984},{"x":446.2784118652344,"y":52.66693878173828},{"x":452.2523498535156,"y":251.8555145263672},{"x":458.1452331542969,"y":225.6822967529297},{"x":464.1955871582031,"y":197.71438598632812},{"x":470.90045166015625,"y":166.6679229736328},{"x":478.2327575683594,"y":132.30064392089844},{"x":486.47454833984375,"y":93.977294921875},{"x":495.2408142089844,"y":51.687469482421875},{"x":488.62860107421875,"y":248.90090942382812},{"x":495.4351501464844,"y":222.91180419921875},{"x":503.1499938964844,"y":194.7021026611328},{"x":512.193603515625,"y":164.06069946289062},{"x":521.641845703125,"y":130.09889221191406},{"x":531.892333984375,"y":92.51961517333984},{"x":544.0599365234375,"y":50.10550308227539},{"x":524.0328369140625,"y":245.86837768554688},{"x":532.7142944335938,"y":220.51441955566406},{"x":542.02197265625,"y":192.45697021484375},{"x":552.8551025390625,"y":161.585693359375},{"x":564.2408447265625,"y":128.01702880859375},{"x":577.0098266601562,"y":90.27936553955078},{"x":591.05908203125,"y":48.805057525634766},{"x":558.7938842773438,"y":242.95257568359375},{"x":568.64306640625,"y":217.80140686035156},{"x":579.8557739257812,"y":190.03799438476562},{"x":591.3824462890625,"y":159.99497985839844},{"x":605.5491943359375,"y":126.30232238769531},{"x":620.5157470703125,"y":88.62998962402344},{"x":636.9906005859375,"y":47.291282653808594}],"reprojectionErrors":[{"x":-0.281707763671875,"y":-0.1475830078125},{"x":-0.120025634765625,"y":0.267578125},{"x":-0.265869140625,"y":-0.29248046875},{"x":-0.25750732421875,"y":-0.0236968994140625},{"x":-0.48858642578125,"y":-0.372283935546875},{"x":-0.120086669921875,"y":-0.071197509765625},{"x":-0.05206298828125,"y":-0.050434112548828125},{"x":-0.174896240234375,"y":-0.289886474609375},{"x":-0.323883056640625,"y":-0.11810302734375},{"x":-0.29986572265625,"y":-0.084869384765625},{"x":-0.396514892578125,"y":-0.01141357421875},{"x":0.07330322265625,"y":-0.420501708984375},{"x":-0.139404296875,"y":0.01541900634765625},{"x":0.168853759765625,"y":-0.23323440551757812},{"x":-0.12200927734375,"y":0.02886962890625},{"x":0.127532958984375,"y":0.039886474609375},{"x":0.154296875,"y":-0.0392608642578125},{"x":0.450286865234375,"y":-0.2795562744140625},{"x":0.18109130859375,"y":-0.1544189453125},{"x":-0.07855224609375,"y":-0.24076080322265625},{"x":0.01531982421875,"y":-0.07338714599609375},{"x":0.31494140625,"y":-0.34930419921875},{"x":-0.0257568359375,"y":0.0407562255859375},{"x":0.010467529296875,"y":-0.22613525390625},{"x":0.00732421875,"y":-0.2365264892578125},{"x":0.089752197265625,"y":-0.1972198486328125},{"x":0.09552001953125,"y":-0.022552490234375},{"x":0.557861328125,"y":-0.3821754455566406},{"x":0.05072021484375,"y":-0.3406982421875},{"x":0.366729736328125,"y":0.005401611328125},{"x":0.451873779296875,"y":0.160858154296875},{"x":-0.01318359375,"y":-0.0233154296875},{"x":0.01812744140625,"y":-0.0940093994140625},{"x":0.297607421875,"y":-0.2860260009765625},{"x":-0.10528564453125,"y":-0.038387298583984375},{"x":0.03912353515625,"y":-0.181121826171875},{"x":-0.0142822265625,"y":-0.330108642578125},{"x":0.11737060546875,"y":-0.1473846435546875},{"x":-0.34539794921875,"y":0.1272430419921875},{"x":-0.28521728515625,"y":-0.0453338623046875},{"x":-0.3565673828125,"y":0.29160308837890625},{"x":-0.23974609375,"y":0.07184600830078125},{"x":-0.0255126953125,"y":-0.0675048828125},{"x":0.19708251953125,"y":-0.2794342041015625},{"x":-0.00732421875,"y":-0.2123260498046875},{"x":0.54742431640625,"y":-0.5394134521484375},{"x":-0.30010986328125,"y":-0.3009033203125},{"x":-0.50946044921875,"y":0.3345794677734375},{"x":-0.5433349609375,"y":0.4413948059082031}],"optimisedCameraToObject":{"translation":{"x":-0.0742904716056737,"y":-0.0026714799221209977,"z":0.4608100839703107},"rotation":{"quaternion":{"W":0.6301247703563392,"X":0.38708503579360687,"Y":0.2403651168060594,"Z":-0.6287547689448107}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img12.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":170.4321746826172,"y":341.90228271484375},{"x":165.33706665039062,"y":315.0465087890625},{"x":159.87278747558594,"y":285.4180908203125},{"x":153.80430603027344,"y":252.77764892578125},{"x":147.0646514892578,"y":216.34042358398438},{"x":139.03311157226562,"y":175.98065185546875},{"x":130.38368225097656,"y":130.044677734375},{"x":214.8218994140625,"y":341.4624938964844},{"x":211.91445922851562,"y":314.9837341308594},{"x":208.74978637695312,"y":285.8413391113281},{"x":205.31576538085938,"y":253.7792205810547},{"x":201.27394104003906,"y":218.100830078125},{"x":196.852783203125,"y":178.16571044921875},{"x":191.81439208984375,"y":133.24842834472656},{"x":257.47198486328125,"y":341.1251220703125},{"x":256.5047302246094,"y":315.09686279296875},{"x":255.86619567871094,"y":286.1723327636719},{"x":254.7644500732422,"y":254.71087646484375},{"x":253.5285186767578,"y":219.7490692138672},{"x":252.1372528076172,"y":180.6794891357422},{"x":251.02102661132812,"y":136.49342346191406},{"x":299.76165771484375,"y":340.9991760253906},{"x":300.8038330078125,"y":315.172607421875},{"x":301.9905090332031,"y":286.86676025390625},{"x":303.37066650390625,"y":255.74942016601562},{"x":304.73760986328125,"y":221.07632446289062},{"x":306.5062255859375,"y":182.85748291015625},{"x":308.2633056640625,"y":139.5941925048828},{"x":340.60272216796875,"y":340.8890075683594},{"x":343.0638732910156,"y":315.27313232421875},{"x":346.3029479980469,"y":287.18109130859375},{"x":349.9678039550781,"y":256.57904052734375},{"x":354.1801452636719,"y":222.6277313232422},{"x":357.8994140625,"y":184.9936981201172},{"x":363.7254638671875,"y":142.73194885253906},{"x":380.4703369140625,"y":340.7813720703125},{"x":385.1983337402344,"y":315.40338134765625},{"x":390.498046875,"y":288.09307861328125},{"x":396.2564697265625,"y":257.4713439941406},{"x":402.56243896484375,"y":224.1927032470703},{"x":409.6294250488281,"y":186.9228973388672},{"x":416.7663879394531,"y":145.56228637695312},{"x":419.4684143066406,"y":340.5473937988281},{"x":425.8221435546875,"y":315.7584228515625},{"x":432.87579345703125,"y":288.27734375},{"x":440.3167419433594,"y":258.4720764160156},{"x":449.0898742675781,"y":225.60731506347656},{"x":458.3133544921875,"y":188.77943420410156},{"x":469.2261962890625,"y":148.06704711914062}],"reprojectionErrors":[{"x":0.330718994140625,"y":-0.547576904296875},{"x":0.39398193359375,"y":-0.433197021484375},{"x":0.3160858154296875,"y":-0.23150634765625},{"x":0.2503509521484375,"y":-0.1331939697265625},{"x":0.163543701171875,"y":0.1193084716796875},{"x":0.5522613525390625,"y":-0.001373291015625},{"x":0.5868377685546875,"y":0.339141845703125},{"x":-0.220123291015625,"y":-0.2808837890625},{"x":-0.2027740478515625,"y":-0.22943115234375},{"x":-0.2177276611328125,"y":-0.134368896484375},{"x":-0.2985992431640625,"y":-0.153717041015625},{"x":-0.1628875732421875,"y":-0.097076416015625},{"x":-0.108154296875,"y":0.050567626953125},{"x":0.0170745849609375,"y":0.2327423095703125},{"x":-0.029296875,"y":-0.09600830078125},{"x":0.091766357421875,"y":-0.188018798828125},{"x":-0.1997833251953125,"y":0.059112548828125},{"x":-0.125091552734375,"y":-0.1128082275390625},{"x":-0.0291595458984375,"y":-0.226715087890625},{"x":0.089508056640625,"y":-0.2743988037109375},{"x":-0.2239532470703125,"y":0.0059661865234375},{"x":-0.439971923828125,"y":-0.102630615234375},{"x":-0.37701416015625,"y":-0.09613037109375},{"x":-0.35089111328125,"y":-0.106842041015625},{"x":-0.39404296875,"y":-0.1869049072265625},{"x":-0.27960205078125,"y":-0.05963134765625},{"x":-0.397705078125,"y":-0.3095245361328125},{"x":-0.3043212890625,"y":-0.1518096923828125},{"x":-0.329437255859375,"y":-0.105804443359375},{"x":0.17816162109375,"y":-0.016387939453125},{"x":0.1939697265625,"y":0.1112060546875},{"x":0.11358642578125,"y":-0.059814453125},{"x":-0.131927490234375,"y":-0.1398773193359375},{"x":0.562652587890625,"y":-0.346710205078125},{"x":-0.322357177734375,"y":-0.4181976318359375},{"x":-0.140167236328125,"y":-0.092926025390625},{"x":-0.11883544921875,"y":0.04583740234375},{"x":-0.216827392578125,"y":-0.2646484375},{"x":-0.25323486328125,"y":-0.00274658203125},{"x":-0.23468017578125,"y":-0.2558441162109375},{"x":-0.274139404296875,"y":-0.2187042236328125},{"x":0.443572998046875,"y":-0.44537353515625},{"x":0.05523681640625,"y":0.064300537109375},{"x":0.15264892578125,"y":-0.10491943359375},{"x":0.15753173828125,"y":0.090911865234375},{"x":0.47247314453125,"y":-0.0611572265625},{"x":0.261383056640625,"y":-0.2426300048828125},{"x":0.538726806640625,"y":-0.0579986572265625},{"x":0.228912353515625,"y":-0.212005615234375}],"optimisedCameraToObject":{"translation":{"x":-0.17341738230487444,"y":0.046035323513301016,"z":0.42378380583086844},"rotation":{"quaternion":{"W":0.6715304964911036,"X":0.3506473973092459,"Y":0.2326690071197907,"Z":-0.6098838644927036}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img13.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":262.76361083984375,"y":499.9200439453125},{"x":264.9584045410156,"y":448.22955322265625},{"x":266.9333190917969,"y":401.2371520996094},{"x":268.90008544921875,"y":358.1203308105469},{"x":270.5458984375,"y":318.8116760253906},{"x":272.0640869140625,"y":282.0578308105469},{"x":273.4319763183594,"y":248.19293212890625},{"x":307.8830261230469,"y":485.70123291015625},{"x":307.98736572265625,"y":433.470458984375},{"x":308.09552001953125,"y":386.02191162109375},{"x":308.25653076171875,"y":342.5267028808594},{"x":308.34954833984375,"y":302.6164855957031},{"x":308.3238830566406,"y":265.85662841796875},{"x":308.52349853515625,"y":232.04751586914062},{"x":354.88653564453125,"y":471.071533203125},{"x":352.8216247558594,"y":417.96563720703125},{"x":350.9516906738281,"y":369.990478515625},{"x":349.06622314453125,"y":326.206787109375},{"x":347.8468322753906,"y":286.0317687988281},{"x":346.0003967285156,"y":249.06765747070312},{"x":344.7955627441406,"y":215.01988220214844},{"x":405.24676513671875,"y":455.38885498046875},{"x":400.270751953125,"y":401.5813903808594},{"x":396.39996337890625,"y":353.0518493652344},{"x":392.35113525390625,"y":308.9298095703125},{"x":388.7183837890625,"y":268.8706970214844},{"x":385.4798889160156,"y":231.29025268554688},{"x":382.77899169921875,"y":197.1163787841797},{"x":458.1355285644531,"y":438.9295349121094},{"x":450.8703308105469,"y":384.1285400390625},{"x":443.8312072753906,"y":335.41827392578125},{"x":437.7568664550781,"y":290.8693542480469},{"x":432.1581115722656,"y":250.17408752441406},{"x":427.26214599609375,"y":212.4259796142578},{"x":422.1490478515625,"y":178.54173278808594},{"x":515.221435546875,"y":421.3694763183594},{"x":504.3929748535156,"y":366.0561828613281},{"x":494.8817138671875,"y":316.4093933105469},{"x":486.04327392578125,"y":271.338623046875},{"x":478.1244812011719,"y":230.6515350341797},{"x":470.8302307128906,"y":192.94737243652344},{"x":464.307373046875,"y":158.55499267578125},{"x":575.88232421875,"y":402.7124938964844},{"x":561.2646484375,"y":346.7610778808594},{"x":548.4962158203125,"y":296.3856201171875},{"x":536.8099975585938,"y":250.99893188476562},{"x":526.2396240234375,"y":210.0255584716797},{"x":516.6980590820312,"y":172.23416137695312},{"x":507.98974609375,"y":137.9456787109375}],"reprojectionErrors":[{"x":0.478118896484375,"y":-0.42864990234375},{"x":0.4278564453125,"y":-0.0213623046875},{"x":0.398956298828125,"y":0.112457275390625},{"x":0.2044677734375,"y":0.242828369140625},{"x":0.17803955078125,"y":-0.027069091796875},{"x":0.1439208984375,"y":0.163238525390625},{"x":0.13983154296875,"y":0.144927978515625},{"x":-0.048583984375,"y":-0.015411376953125},{"x":-0.018798828125,"y":0.163726806640625},{"x":-0.017303466796875,"y":0.1693115234375},{"x":-0.090057373046875,"y":0.240264892578125},{"x":-0.11358642578125,"y":0.25164794921875},{"x":-0.034942626953125,"y":0.222320556640625},{"x":-0.1962890625,"y":-0.001007080078125},{"x":0.1705322265625,"y":-0.0189208984375},{"x":0.120025634765625,"y":0.261444091796875},{"x":0.0552978515625,"y":0.214263916015625},{"x":0.1630859375,"y":0.148223876953125},{"x":-0.2579345703125,"y":0.121246337890625},{"x":0.0687255859375,"y":0.0908050537109375},{"x":-0.1395263671875,"y":-0.020782470703125},{"x":-0.09112548828125,"y":0.125518798828125},{"x":0.24761962890625,"y":0.331329345703125},{"x":-0.095916748046875,"y":0.268035888671875},{"x":0.1044921875,"y":0.131195068359375},{"x":0.207550048828125,"y":-0.2935791015625},{"x":0.1956787109375,"y":0.11126708984375},{"x":-0.107666015625,"y":0.0249786376953125},{"x":0.272369384765625,"y":0.05419921875},{"x":0.06732177734375,"y":0.47930908203125},{"x":0.345184326171875,"y":0.039886474609375},{"x":0.269134521484375,"y":-0.058013916015625},{"x":0.24749755859375,"y":-0.1024169921875},{"x":-0.014068603515625,"y":0.318084716796875},{"x":0.348114013671875,"y":-0.1280364990234375},{"x":-0.093017578125,"y":-0.00775146484375},{"x":0.075531005859375,"y":0.162567138671875},{"x":-0.025787353515625,"y":0.1221923828125},{"x":0.098419189453125,"y":0.185394287109375},{"x":0.07928466796875,"y":-0.091094970703125},{"x":0.11102294921875,"y":0.16796875},{"x":-0.03729248046875,"y":0.1955108642578125},{"x":-0.20709228515625,"y":-0.176788330078125},{"x":0.150390625,"y":-0.121551513671875},{"x":0.10699462890625,"y":0.0557861328125},{"x":0.21771240234375,"y":0.108428955078125},{"x":0.2763671875,"y":-0.0669708251953125},{"x":0.22821044921875,"y":0.2028350830078125},{"x":0.1510009765625,"y":0.1338043212890625}],"optimisedCameraToObject":{"translation":{"x":-0.08882699765739929,"y":0.12561042342467743,"z":0.31077800332331695},"rotation":{"quaternion":{"W":0.5674741215244988,"X":-0.366172540622608,"Y":-0.04444170037778998,"Z":-0.7361492560354277}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img14.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":158.6150665283203,"y":478.2942199707031},{"x":163.29234313964844,"y":428.1709289550781},{"x":167.7926483154297,"y":382.22454833984375},{"x":171.58248901367188,"y":338.81475830078125},{"x":175.2389678955078,"y":297.82989501953125},{"x":178.96669006347656,"y":259.9350891113281},{"x":182.67816162109375,"y":224.08055114746094},{"x":211.9612579345703,"y":475.63104248046875},{"x":214.83175659179688,"y":426.70452880859375},{"x":217.25164794921875,"y":380.7733154296875},{"x":219.56234741210938,"y":337.6633605957031},{"x":221.92604064941406,"y":297.9463806152344},{"x":224.0456085205078,"y":260.0238952636719},{"x":226.3800506591797,"y":224.33413696289062},{"x":263.1701965332031,"y":472.9099426269531},{"x":264.7967529296875,"y":424.1734313964844},{"x":265.3115234375,"y":379.29315185546875},{"x":266.13763427734375,"y":337.1464538574219},{"x":267.08636474609375,"y":297.7409362792969},{"x":267.52960205078125,"y":260.6214599609375},{"x":268.3534851074219,"y":224.95855712890625},{"x":313.9393310546875,"y":470.1596984863281},{"x":313.4972229003906,"y":422.7940979003906},{"x":312.73101806640625,"y":378.52130126953125},{"x":312.02447509765625,"y":336.2854309082031},{"x":311.2861633300781,"y":297.24481201171875},{"x":310.9100646972656,"y":260.3515625},{"x":310.33587646484375,"y":225.6849365234375},{"x":363.04180908203125,"y":468.3505859375},{"x":360.4915771484375,"y":420.9019775390625},{"x":358.4830017089844,"y":377.01031494140625},{"x":356.5301818847656,"y":335.7756652832031},{"x":354.605224609375,"y":297.21551513671875},{"x":352.5280456542969,"y":260.74853515625},{"x":351.06591796875,"y":226.16741943359375},{"x":411.2150573730469,"y":465.7917785644531},{"x":407.0084533691406,"y":419.19732666015625},{"x":403.52960205078125,"y":376.08612060546875},{"x":399.92645263671875,"y":334.96826171875},{"x":397.10784912109375,"y":297.02392578125},{"x":393.9640197753906,"y":260.606201171875},{"x":391.2037353515625,"y":226.49575805664062},{"x":457.8764343261719,"y":463.8181457519531},{"x":452.56231689453125,"y":417.5245056152344},{"x":446.8638000488281,"y":374.4830627441406},{"x":442.5096435546875,"y":334.6591491699219},{"x":437.9360046386719,"y":296.51165771484375},{"x":433.99371337890625,"y":260.8833312988281},{"x":430.1219482421875,"y":227.06622314453125}],"reprojectionErrors":[{"x":0.453948974609375,"y":-0.521148681640625},{"x":0.3511962890625,"y":0.053863525390625},{"x":0.1165924072265625,"y":-0.245269775390625},{"x":0.3138427734375,"y":-0.1015625},{"x":0.3922882080078125,"y":0.31414794921875},{"x":0.17047119140625,"y":0.088836669921875},{"x":-0.243682861328125,"y":0.053924560546875},{"x":-0.017486572265625,"y":-0.34161376953125},{"x":-0.173370361328125,"y":-0.28802490234375},{"x":-0.0598907470703125,"y":-0.009613037109375},{"x":-9.1552734375E-4,"y":0.3558349609375},{"x":-0.1432952880859375,"y":-0.036224365234375},{"x":-0.1763916015625,"y":0.17303466796875},{"x":-0.5473175048828125,"y":0.3338165283203125},{"x":0.358123779296875,"y":-0.050079345703125},{"x":-0.32635498046875,"y":0.4697265625},{"x":0.03863525390625,"y":0.273895263671875},{"x":0.035980224609375,"y":0.184326171875},{"x":-0.140411376953125,"y":-0.070159912109375},{"x":0.14215087890625,"y":-0.266326904296875},{"x":0.00164794921875,"y":0.220306396484375},{"x":-0.06536865234375,"y":0.322601318359375},{"x":-0.371246337890625,"y":0.109222412109375},{"x":-0.304412841796875,"y":-0.132720947265625},{"x":-0.25323486328125,"y":0.362335205078125},{"x":-0.13031005859375,"y":0.181243896484375},{"x":-0.33319091796875,"y":0.14739990234375},{"x":-0.30474853515625,"y":-0.0170135498046875},{"x":-0.01239013671875,"y":-0.196014404296875},{"x":0.17767333984375,"y":0.293731689453125},{"x":-0.0218505859375,"y":0.21728515625},{"x":-0.139312744140625,"y":0.194183349609375},{"x":-0.1593017578125,"y":-0.0394287109375},{"x":0.087158203125,"y":-0.119598388671875},{"x":-0.176971435546875,"y":-0.0316162109375},{"x":-0.1741943359375,"y":0.0830078125},{"x":0.13360595703125,"y":0.32177734375},{"x":-0.037689208984375,"y":-0.002716064453125},{"x":0.140869140625,"y":0.32861328125},{"x":-0.259857177734375,"y":-0.10284423828125},{"x":-0.14801025390625,"y":0.139251708984375},{"x":-0.24822998046875,"y":0.0874176025390625},{"x":0.075714111328125,"y":-0.17706298828125},{"x":0.022003173828125,"y":0.3477783203125},{"x":0.691436767578125,"y":0.472320556640625},{"x":0.324127197265625,"y":-0.030548095703125},{"x":0.456573486328125,"y":0.14947509765625},{"x":0.213623046875,"y":-0.034454345703125},{"x":0.1346435546875,"y":-0.0555877685546875}],"optimisedCameraToObject":{"translation":{"x":-0.14851841315991196,"y":0.11458928837243038,"z":0.32283188441216637},"rotation":{"quaternion":{"W":0.6660391952524076,"X":-0.11961405034648281,"Y":-0.23290290626195947,"Z":-0.6984558007504607}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img15.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":166.7033233642578,"y":413.7906494140625},{"x":166.68040466308594,"y":362.6614990234375},{"x":166.7943572998047,"y":313.9007263183594},{"x":166.58901977539062,"y":268.26812744140625},{"x":166.82815551757812,"y":224.51942443847656},{"x":166.71559143066406,"y":182.86224365234375},{"x":166.89645385742188,"y":143.30496215820312},{"x":217.39837646484375,"y":414.633544921875},{"x":216.5741729736328,"y":365.475341796875},{"x":215.24147033691406,"y":319.20159912109375},{"x":214.10304260253906,"y":275.0282287597656},{"x":213.2749786376953,"y":233.12445068359375},{"x":211.93817138671875,"y":192.99771118164062},{"x":211.00819396972656,"y":154.68490600585938},{"x":263.99261474609375,"y":415.2914123535156},{"x":261.67205810546875,"y":368.0688781738281},{"x":259.6477966308594,"y":324.1304016113281},{"x":257.14105224609375,"y":281.494140625},{"x":255.48854064941406,"y":240.92327880859375},{"x":253.36288452148438,"y":202.0071258544922},{"x":251.60157775878906,"y":165.07020568847656},{"x":306.8641662597656,"y":415.4223937988281},{"x":303.3005065917969,"y":370.8508605957031},{"x":300.5548095703125,"y":328.0719909667969},{"x":297.3207702636719,"y":286.942626953125},{"x":294.8061218261719,"y":248.09698486328125},{"x":291.9878234863281,"y":210.31629943847656},{"x":289.477783203125,"y":174.8060760498047},{"x":345.5438537597656,"y":416.1014709472656},{"x":341.42596435546875,"y":373.5184020996094},{"x":338.0846252441406,"y":331.9765625},{"x":334.80499267578125,"y":292.4921875},{"x":330.9621276855469,"y":254.8128662109375},{"x":327.83349609375,"y":218.41290283203125},{"x":324.4891662597656,"y":183.8994598388672},{"x":382.09088134765625,"y":416.8710632324219},{"x":376.96636962890625,"y":374.9570617675781},{"x":372.9924621582031,"y":335.63275146484375},{"x":369.01239013671875,"y":297.47882080078125},{"x":364.4588928222656,"y":261.0359802246094},{"x":360.9498291015625,"y":225.4192352294922},{"x":357.2003479003906,"y":192.03677368164062},{"x":415.73114013671875,"y":417.5086364746094},{"x":410.447998046875,"y":377.0887145996094},{"x":405.7275695800781,"y":339.0743103027344},{"x":400.8468933105469,"y":301.5941162109375},{"x":395.9844665527344,"y":266.51226806640625},{"x":391.83746337890625,"y":232.3808135986328},{"x":388.1025085449219,"y":200.16683959960938}],"reprojectionErrors":[{"x":-0.0312957763671875,"y":-0.24261474609375},{"x":0.061431884765625,"y":-0.094085693359375},{"x":0.02081298828125,"y":0.3343505859375},{"x":0.302703857421875,"y":0.078369140625},{"x":0.1431427001953125,"y":0.1982574462890625},{"x":0.3380584716796875,"y":0.3204193115234375},{"x":0.2421417236328125,"y":0.286346435546875},{"x":0.027008056640625,"y":-0.2457275390625},{"x":-0.3797760009765625,"y":0.1348876953125},{"x":-0.2088470458984375,"y":0.056915283203125},{"x":-0.1680908203125,"y":0.124725341796875},{"x":-0.37823486328125,"y":0.006744384765625},{"x":-0.0243682861328125,"y":0.0484161376953125},{"x":-0.025848388671875,"y":0.0792694091796875},{"x":-0.153564453125,"y":-0.141326904296875},{"x":-0.149749755859375,"y":0.323211669921875},{"x":-0.32305908203125,"y":-0.26593017578125},{"x":0.09686279296875,"y":-0.085601806640625},{"x":-0.234405517578125,"y":-0.04302978515625},{"x":0.003509521484375,"y":0.1414642333984375},{"x":-0.03326416015625,"y":0.02398681640625},{"x":-0.4129638671875,"y":0.422119140625},{"x":-0.07537841796875,"y":0.093719482421875},{"x":-0.398681640625,"y":0.0303955078125},{"x":-0.0872802734375,"y":0.234375},{"x":-0.35870361328125,"y":-0.05694580078125},{"x":-0.1988525390625,"y":0.258056640625},{"x":-0.22784423828125,"y":-0.1332855224609375},{"x":0.170745849609375,"y":0.377685546875},{"x":0.2989501953125,"y":-0.223968505859375},{"x":-0.16375732421875,"y":0.03759765625},{"x":-0.5147705078125,"y":0.020416259765625},{"x":-0.140350341796875,"y":-0.1380157470703125},{"x":-0.32818603515625,"y":-0.017181396484375},{"x":-0.15777587890625,"y":-0.3208160400390625},{"x":-0.07806396484375,"y":0.18975830078125},{"x":0.414276123046875,"y":0.50726318359375},{"x":-0.037078857421875,"y":0.002777099609375},{"x":-0.288543701171875,"y":-0.016998291015625},{"x":0.215087890625,"y":-0.196044921875},{"x":-0.155181884765625,"y":0.25579833984375},{"x":-0.1246337890625,"y":-0.1569671630859375},{"x":-0.05810546875,"y":0.086761474609375},{"x":0.05157470703125,"y":0.38494873046875},{"x":-0.178955078125,"y":-0.07708740234375},{"x":-0.04046630859375,"y":0.470611572265625},{"x":0.2760009765625,"y":0.070770263671875},{"x":0.0616455078125,"y":0.085540771484375},{"x":-0.39080810546875,"y":-0.5313720703125}],"optimisedCameraToObject":{"translation":{"x":-0.13440901622362147,"y":0.07866297200061276,"z":0.3031545075436054},"rotation":{"quaternion":{"W":0.6543862227437176,"X":0.09534956453136986,"Y":-0.3656435727205609,"Z":-0.6549747397839336}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/a5f65692-1b65-462f-b810-4be69688ece6/imgs/800x600/img16.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/vision_settings/Camera Calibrations/8-800-600.json b/vision_settings/Camera Calibrations/8-800-600.json new file mode 100644 index 00000000..c1826991 --- /dev/null +++ b/vision_settings/Camera Calibrations/8-800-600.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[686.2323478032447,0.0,411.3616022496808,0.0,686.3856550543791,306.2353552097819,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.041129679810063574,-0.05335243548013431,-2.296335413053231E-4,-0.0010241449755942617,0.019409719567788492,-0.001487867889709611,0.002055984634016473,-7.709355085725221E-4]},"calobjectWarp":[6.168185441466654E-5,9.970782602257534E-5],"observations":[{"locationInObjectSpace":[{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":103.82411193847656,"y":491.7610168457031},{"x":99.17857360839844,"y":425.34765625},{"x":94.29056549072266,"y":359.90380859375},{"x":89.49625396728516,"y":296.5452880859375},{"x":84.49528503417969,"y":233.76797485351562},{"x":80.03936004638672,"y":172.45074462890625},{"x":162.93345642089844,"y":479.1929931640625},{"x":157.44485473632812,"y":417.4159851074219},{"x":153.01925659179688,"y":357.522705078125},{"x":147.8084716796875,"y":297.8917541503906},{"x":142.86599731445312,"y":239.8527374267578},{"x":137.81509399414062,"y":182.3473358154297},{"x":218.21273803710938,"y":526.790283203125},{"x":213.00051879882812,"y":468.1183776855469},{"x":207.9756317138672,"y":410.8489990234375},{"x":202.79283142089844,"y":355.0428771972656},{"x":198.0396728515625,"y":299.2558898925781},{"x":192.9414520263672,"y":244.49668884277344},{"x":188.02430725097656,"y":191.27621459960938},{"x":262.894287109375,"y":513.142578125},{"x":257.39239501953125,"y":458.6457824707031},{"x":252.33607482910156,"y":404.7404479980469},{"x":247.309814453125,"y":352.1044616699219},{"x":242.1410675048828,"y":300.7380065917969},{"x":237.14561462402344,"y":249.31033325195312},{"x":232.3088836669922,"y":199.14071655273438},{"x":301.95745849609375,"y":501.69775390625},{"x":296.3825378417969,"y":450.0264892578125},{"x":291.1920166015625,"y":399.74334716796875},{"x":286.2317810058594,"y":350.1044006347656},{"x":281.1453857421875,"y":301.2030944824219},{"x":276.1361389160156,"y":253.4592742919922},{"x":271.31781005859375,"y":206.18775939941406},{"x":336.3002624511719,"y":491.2223815917969},{"x":331.02337646484375,"y":442.5637512207031},{"x":326.0343933105469,"y":395.20556640625},{"x":321.0224914550781,"y":348.359130859375},{"x":315.8292236328125,"y":302.2513732910156},{"x":311.2424621582031,"y":257.1619567871094},{"x":306.02862548828125,"y":212.1380157470703},{"x":367.14910888671875,"y":481.89117431640625},{"x":361.66107177734375,"y":436.0162048339844},{"x":357.20263671875,"y":391.486572265625},{"x":351.9082946777344,"y":346.6797790527344},{"x":346.8497009277344,"y":303.11968994140625},{"x":342.11865234375,"y":260.1168518066406},{"x":337.019287109375,"y":217.4978790283203}],"reprojectionErrors":[{"x":0.10103607177734375,"y":-0.260528564453125},{"x":-0.1377410888671875,"y":-0.164947509765625},{"x":-0.0221099853515625,"y":0.295562744140625},{"x":0.1081085205078125,"y":-0.0389404296875},{"x":0.549774169921875,"y":0.2935333251953125},{"x":0.5478286743164062,"y":0.3736572265625},{"x":-0.60107421875,"y":-0.16900634765625},{"x":-0.2020416259765625,"y":0.124786376953125},{"x":-0.756927490234375,"y":-0.3154296875},{"x":-0.4208984375,"y":0.09613037109375},{"x":-0.2506256103515625,"y":-0.004241943359375},{"x":0.1275634765625,"y":0.408935546875},{"x":0.03118896484375,"y":-0.23358154296875},{"x":-0.0633087158203125,"y":0.099822998046875},{"x":-0.2372283935546875,"y":0.061981201171875},{"x":-0.148468017578125,"y":-0.43817138671875},{"x":-0.3875885009765625,"y":0.01422119140625},{"x":-0.182769775390625,"y":0.3824920654296875},{"x":-0.062957763671875,"y":0.1286773681640625},{"x":-0.336395263671875,"y":0.1932373046875},{"x":-0.179290771484375,"y":0.121826171875},{"x":-0.3651580810546875,"y":0.363372802734375},{"x":-0.48126220703125,"y":0.214813232421875},{"x":-0.3577880859375,"y":-0.348297119140625},{"x":-0.3131103515625,"y":-0.0185394287109375},{"x":-0.3351898193359375,"y":-0.13775634765625},{"x":-0.335845947265625,"y":-0.009490966796875},{"x":-0.098052978515625,"y":0.40496826171875},{"x":-0.147552490234375,"y":0.23089599609375},{"x":-0.33270263671875,"y":0.191131591796875},{"x":-0.29949951171875,"y":0.171844482421875},{"x":-0.253570556640625,"y":-0.2664642333984375},{"x":-0.311004638671875,"y":-0.4576416015625},{"x":0.0220947265625,"y":0.125823974609375},{"x":9.1552734375E-4,"y":0.45904541015625},{"x":-0.216400146484375,"y":0.203857421875},{"x":-0.321319580078125,"y":0.131072998046875},{"x":-0.157562255859375,"y":-0.0035400390625},{"x":-0.515106201171875,"y":-0.496368408203125},{"x":-0.162445068359375,"y":-0.4107513427734375},{"x":0.208953857421875,"y":0.21527099609375},{"x":0.4595947265625,"y":0.37811279296875},{"x":-0.2327880859375,"y":-0.166290283203125},{"x":-0.004730224609375,"y":0.189300537109375},{"x":0.07012939453125,"y":-0.09381103515625},{"x":-0.10186767578125,"y":-0.340545654296875},{"x":0.17327880859375,"y":-0.391448974609375}],"optimisedCameraToObject":{"translation":{"x":-0.1271874263895211,"y":0.12109763618262935,"z":0.23834782175021396},"rotation":{"quaternion":{"W":0.6074022879346237,"X":0.26425702121048406,"Y":-0.37107632583257505,"Z":-0.6507941669678231}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":335.224365234375,"y":528.188232421875},{"x":327.4248046875,"y":466.20147705078125},{"x":319.9888916015625,"y":406.641845703125},{"x":312.1087341308594,"y":348.0646667480469},{"x":305.0378723144531,"y":290.4179992675781},{"x":297.2485046386719,"y":234.2752227783203},{"x":290.8478698730469,"y":179.27041625976562},{"x":385.2159118652344,"y":514.70751953125},{"x":377.0328674316406,"y":456.09564208984375},{"x":369.4987487792969,"y":398.8832702636719},{"x":361.62158203125,"y":343.48095703125},{"x":354.3725891113281,"y":288.7449951171875},{"x":346.8710021972656,"y":235.46771240234375},{"x":339.485595703125,"y":183.0224609375},{"x":430.4659729003906,"y":502.17523193359375},{"x":422.0343017578125,"y":446.9033203125},{"x":413.8912048339844,"y":392.5944519042969},{"x":406.38421630859375,"y":339.9102783203125},{"x":398.84954833984375,"y":287.8819580078125},{"x":391.30706787109375,"y":236.34042358398438},{"x":384.1333312988281,"y":186.67678833007812},{"x":471.2261657714844,"y":491.27349853515625},{"x":462.90643310546875,"y":438.1165466308594},{"x":455.065673828125,"y":386.4566345214844},{"x":447.1015625,"y":336.10736083984375},{"x":439.6888122558594,"y":286.2560729980469},{"x":432.01263427734375,"y":237.4574737548828},{"x":424.7307434082031,"y":189.59495544433594},{"x":508.5071105957031,"y":480.9925537109375},{"x":500.445556640625,"y":430.3984069824219},{"x":492.1613464355469,"y":381.2522277832031},{"x":484.55816650390625,"y":333.07794189453125},{"x":476.8962707519531,"y":285.3346252441406},{"x":469.4720153808594,"y":238.4569549560547},{"x":461.9378967285156,"y":192.51113891601562},{"x":543.1734008789062,"y":471.6739196777344},{"x":534.7451171875,"y":423.2898254394531},{"x":526.7666015625,"y":376.31683349609375},{"x":518.9602661132812,"y":329.5792541503906},{"x":511.3671569824219,"y":284.0814514160156},{"x":504.0712890625,"y":239.30093383789062},{"x":496.48516845703125,"y":195.06121826171875},{"x":574.4671630859375,"y":463.28125},{"x":566.1998901367188,"y":416.91265869140625},{"x":558.2867431640625,"y":371.4350891113281},{"x":550.5339965820312,"y":327.0494384765625},{"x":543.1658325195312,"y":283.0921936035156},{"x":535.560546875,"y":239.99440002441406},{"x":528.23095703125,"y":197.35150146484375}],"reprojectionErrors":[{"x":0.006683349609375,"y":-0.318603515625},{"x":-0.0987548828125,"y":0.355499267578125},{"x":-0.382904052734375,"y":-0.051666259765625},{"x":-0.04443359375,"y":-0.144012451171875},{"x":-0.34326171875,"y":0.084075927734375},{"x":0.242431640625,"y":0.01507568359375},{"x":-0.400390625,"y":-0.0272064208984375},{"x":-0.179046630859375,"y":-0.3675537109375},{"x":-0.0323486328125,"y":0.134002685546875},{"x":-0.354736328125,"y":0.4483642578125},{"x":-0.160369873046875,"y":0.12310791015625},{"x":-0.426361083984375,"y":0.261993408203125},{"x":-0.277587890625,"y":0.03448486328125},{"x":-0.088165283203125,"y":0.0307159423828125},{"x":-0.384490966796875,"y":-0.064453125},{"x":-0.06048583984375,"y":-0.020233154296875},{"x":0.14886474609375,"y":0.15869140625},{"x":-0.109649658203125,"y":-0.22564697265625},{"x":-0.177764892578125,"y":-0.239166259765625},{"x":-0.08050537109375,"y":0.25390625},{"x":-0.199493408203125,"y":-0.1693878173828125},{"x":-0.2021484375,"y":-0.271514892578125},{"x":-0.015869140625,"y":0.2662353515625},{"x":-0.1409912109375,"y":0.305694580078125},{"x":0.01953125,"y":0.00152587890625},{"x":-0.21405029296875,"y":0.13592529296875},{"x":-0.031829833984375,"y":0.1250457763671875},{"x":-0.096160888671875,"y":0.057464599609375},{"x":-0.099853515625,"y":-0.127166748046875},{"x":-0.16290283203125,"y":0.21942138671875},{"x":0.15777587890625,"y":0.0306396484375},{"x":-0.04638671875,"y":-0.245361328125},{"x":-0.040374755859375,"y":-0.094451904296875},{"x":-0.124969482421875,"y":0.0229644775390625},{"x":0.042999267578125,"y":0.015899658203125},{"x":-0.4910888671875,"y":-0.096160888671875},{"x":-0.1522216796875,"y":0.20599365234375},{"x":-0.1085205078125,"y":-0.0657958984375},{"x":-0.08697509765625,"y":0.239471435546875},{"x":-0.1329345703125,"y":0.093719482421875},{"x":-0.3345947265625,"y":-0.0034027099609375},{"x":-0.10845947265625,"y":0.102569580078125},{"x":-0.239990234375,"y":-0.245361328125},{"x":-0.0069580078125,"y":0.02655029296875},{"x":0.02020263671875,"y":0.178192138671875},{"x":0.03094482421875,"y":-0.01324462890625},{"x":-0.202880859375,"y":0.094573974609375},{"x":-0.06341552734375,"y":0.050262451171875},{"x":-0.0672607421875,"y":0.23870849609375}],"optimisedCameraToObject":{"translation":{"x":-0.048439048971156674,"y":0.1187591792157107,"z":0.2689018688596921},"rotation":{"quaternion":{"W":0.6331309727473067,"X":0.16253116621860872,"Y":-0.28036812859003574,"Z":-0.7029384779812452}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":460.7552185058594,"y":475.9663391113281},{"x":451.58056640625,"y":416.1165466308594},{"x":442.93572998046875,"y":358.177734375},{"x":434.1734619140625,"y":301.2997741699219},{"x":426.0086975097656,"y":245.2238311767578},{"x":417.9802551269531,"y":189.7224884033203},{"x":409.9366149902344,"y":135.37387084960938},{"x":510.2080993652344,"y":465.2113037109375},{"x":501.18450927734375,"y":407.76947021484375},{"x":492.33343505859375,"y":352.1107177734375},{"x":483.7104187011719,"y":296.4562683105469},{"x":475.3577575683594,"y":242.78756713867188},{"x":467.28668212890625,"y":188.95913696289062},{"x":459.01019287109375,"y":136.783447265625},{"x":556.1686401367188,"y":455.2332458496094},{"x":547.2515869140625,"y":399.9815368652344},{"x":538.1376342773438,"y":345.8220520019531},{"x":529.6541748046875,"y":292.05706787109375},{"x":521.2094116210938,"y":239.9874267578125},{"x":512.9227905273438,"y":188.3583221435547},{"x":504.8219299316406,"y":137.845703125},{"x":600.3338623046875,"y":446.1347961425781},{"x":590.7820434570312,"y":392.27447509765625},{"x":581.9088134765625,"y":340.1315002441406},{"x":573.2041015625,"y":288.45660400390625},{"x":564.661865234375,"y":237.95492553710938},{"x":556.1996459960938,"y":187.93959045410156},{"x":547.9376831054688,"y":138.6388702392578},{"x":641.1218872070312,"y":437.2884216308594},{"x":631.85888671875,"y":385.5939025878906},{"x":622.4380493164062,"y":334.38861083984375},{"x":613.7677001953125,"y":284.9160461425781},{"x":605.0458984375,"y":235.96600341796875},{"x":596.5516357421875,"y":187.11972045898438},{"x":588.654052734375,"y":139.3709716796875},{"x":679.5311889648438,"y":428.67218017578125},{"x":670.091552734375,"y":379.0156555175781},{"x":661.0838012695312,"y":329.9858703613281},{"x":652.2525634765625,"y":281.3902893066406},{"x":643.7417602539062,"y":233.6183624267578},{"x":635.1710205078125,"y":186.4091033935547},{"x":626.7968139648438,"y":140.11798095703125},{"x":715.4915771484375,"y":421.5492248535156},{"x":706.1629638671875,"y":372.91729736328125},{"x":697.0136108398438,"y":325.0469970703125},{"x":688.2810668945312,"y":278.0255432128906},{"x":679.6300048828125,"y":231.7068328857422},{"x":671.1737060546875,"y":185.86756896972656},{"x":663.000244140625,"y":141.00778198242188}],"reprojectionErrors":[{"x":-0.899200439453125,"y":-0.056610107421875},{"x":-0.478302001953125,"y":0.484649658203125},{"x":-0.4168701171875,"y":0.19775390625},{"x":-0.073028564453125,"y":-0.101715087890625},{"x":-0.166900634765625,"y":-0.1881256103515625},{"x":-0.24224853515625,"y":0.1341552734375},{"x":-0.15228271484375,"y":0.2564544677734375},{"x":-0.418914794921875,"y":-0.0335693359375},{"x":-0.29046630859375,"y":0.252044677734375},{"x":-0.166046142578125,"y":-0.238006591796875},{"x":-0.106414794921875,"y":0.24383544921875},{"x":-0.1588134765625,"y":-0.31396484375},{"x":-0.3392333984375,"y":0.2053375244140625},{"x":-0.165252685546875,"y":-0.0384521484375},{"x":0.19854736328125,"y":-0.06048583984375},{"x":0.1170654296875,"y":0.034271240234375},{"x":0.3984375,"y":-0.0235595703125},{"x":0.2103271484375,"y":0.43548583984375},{"x":0.13970947265625,"y":0.083221435546875},{"x":0.06268310546875,"y":0.1483154296875},{"x":-0.052825927734375,"y":-0.0704193115234375},{"x":-0.4088134765625,"y":-0.31256103515625},{"x":0.07257080078125,"y":0.252716064453125},{"x":0.038330078125,"y":-0.020751953125},{"x":-0.00616455078125,"y":0.090484619140625},{"x":-0.05938720703125,"y":-0.143524169921875},{"x":-0.04327392578125,"y":-0.0597991943359375},{"x":-0.082275390625,"y":0.0903472900390625},{"x":-0.3671875,"y":-0.225494384765625},{"x":-0.220458984375,"y":-0.087799072265625},{"x":0.243896484375,"y":0.384063720703125},{"x":0.11297607421875,"y":-0.077056884765625},{"x":0.18438720703125,"y":-0.2835845947265625},{"x":0.175048828125,"y":0.1613311767578125},{"x":-0.288330078125,"y":0.2428436279296875},{"x":-0.41961669921875,"y":0.167266845703125},{"x":-0.12030029296875,"y":-0.10650634765625},{"x":-0.0965576171875,"y":-0.233856201171875},{"x":-0.0972900390625,"y":-0.04376220703125},{"x":-0.2706298828125,"y":0.053466796875},{"x":-0.2401123046875,"y":0.29876708984375},{"x":-0.26611328125,"y":0.3172760009765625},{"x":-0.2713623046875,"y":-0.446044921875},{"x":-0.0889892578125,"y":-0.219268798828125},{"x":0.06683349609375,"y":-0.026580810546875},{"x":-0.04547119140625,"y":0.02496337890625},{"x":-0.09454345703125,"y":0.062347412109375},{"x":-0.197509765625,"y":0.2904052734375},{"x":-0.446044921875,"y":0.1912384033203125}],"optimisedCameraToObject":{"translation":{"x":0.0014587781007360005,"y":0.09988770520072872,"z":0.28092451016215675},"rotation":{"quaternion":{"W":0.6473499091114335,"X":0.10152477648182164,"Y":-0.19720304160849356,"Z":-0.7292062639021237}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":394.41448974609375,"y":434.7764892578125},{"x":393.29974365234375,"y":380.8996887207031},{"x":392.6995544433594,"y":328.0668640136719},{"x":391.5551452636719,"y":276.0853576660156},{"x":390.26348876953125,"y":224.7906951904297},{"x":389.5423278808594,"y":173.769287109375},{"x":388.6612548828125,"y":123.93451690673828},{"x":446.17340087890625,"y":432.36712646484375},{"x":444.5855712890625,"y":379.4296569824219},{"x":443.0414123535156,"y":328.03643798828125},{"x":441.95587158203125,"y":276.74359130859375},{"x":440.61865234375,"y":226.3883056640625},{"x":439.300048828125,"y":176.02426147460938},{"x":437.8090515136719,"y":127.09513092041016},{"x":495.2294616699219,"y":430.3479919433594},{"x":493.3853454589844,"y":378.766845703125},{"x":491.9098205566406,"y":327.3250732421875},{"x":490.33612060546875,"y":276.9599609375},{"x":488.6735534667969,"y":227.4557647705078},{"x":487.0954895019531,"y":178.28176879882812},{"x":485.6975402832031,"y":129.87681579589844},{"x":543.6412353515625,"y":428.4253845214844},{"x":541.1190795898438,"y":377.0787048339844},{"x":539.4447631835938,"y":327.2288818359375},{"x":537.4924926757812,"y":277.62921142578125},{"x":535.6904907226562,"y":228.80458068847656},{"x":533.936767578125,"y":180.2139129638672},{"x":531.8428955078125,"y":132.85440063476562},{"x":590.0809936523438,"y":426.7692565917969},{"x":587.6957397460938,"y":376.20123291015625},{"x":585.2615966796875,"y":326.95001220703125},{"x":583.12939453125,"y":278.0119934082031},{"x":580.877197265625,"y":230.02615356445312},{"x":578.944580078125,"y":182.2609405517578},{"x":577.06103515625,"y":135.29783630371094},{"x":635.3050537109375,"y":424.97125244140625},{"x":632.4027099609375,"y":375.0419616699219},{"x":629.8209838867188,"y":326.93121337890625},{"x":627.6649169921875,"y":278.5201721191406},{"x":625.3280639648438,"y":231.0463104248047},{"x":622.897705078125,"y":184.0327606201172},{"x":620.7279052734375,"y":137.90518188476562},{"x":678.95361328125,"y":422.9987487792969},{"x":675.9857788085938,"y":374.2488708496094},{"x":673.0042724609375,"y":326.0615234375},{"x":670.5963134765625,"y":279.006103515625},{"x":668.0258178710938,"y":232.07894897460938},{"x":665.4950561523438,"y":185.88914489746094},{"x":663.01123046875,"y":140.04356384277344}],"reprojectionErrors":[{"x":-0.204071044921875,"y":-0.122802734375},{"x":-0.08038330078125,"y":0.152862548828125},{"x":-0.45306396484375,"y":0.1513671875},{"x":-0.2637939453125,"y":0.044464111328125},{"x":0.09002685546875,"y":-0.0236663818359375},{"x":-0.10980224609375,"y":0.341094970703125},{"x":-0.133331298828125,"y":0.20648193359375},{"x":-0.5885009765625,"y":0.123382568359375},{"x":-0.33966064453125,"y":0.376251220703125},{"x":-0.11016845703125,"y":-0.174041748046875},{"x":-0.315643310546875,"y":-0.103607177734375},{"x":-0.24639892578125,"y":-0.2689056396484375},{"x":-0.17327880859375,"y":0.257720947265625},{"x":0.094146728515625,"y":0.014556884765625},{"x":0.030181884765625,"y":0.05401611328125},{"x":0.21075439453125,"y":-0.1661376953125},{"x":0.052490234375,"y":0.191009521484375},{"x":0.021453857421875,"y":0.169158935546875},{"x":0.107574462890625,"y":-0.034454345703125},{"x":0.13677978515625,"y":0.093109130859375},{"x":0.0128173828125,"y":0.095733642578125},{"x":-0.31634521484375,"y":-0.0411376953125},{"x":0.2391357421875,"y":0.3560791015625},{"x":-0.0184326171875,"y":-0.050018310546875},{"x":0.03582763671875,"y":-0.03094482421875},{"x":-0.027099609375,"y":-0.1292266845703125},{"x":-0.10601806640625,"y":0.1791839599609375},{"x":0.1866455078125,"y":-0.11944580078125},{"x":-0.216552734375,"y":-0.335662841796875},{"x":-0.0811767578125,"y":0.104888916015625},{"x":0.142333984375,"y":-0.09979248046875},{"x":0.10223388671875,"y":0.036468505859375},{"x":0.21954345703125,"y":-0.1422119140625},{"x":0.05377197265625,"y":0.0794219970703125},{"x":-0.12548828125,"y":0.1040496826171875},{"x":-0.34844970703125,"y":-0.4246826171875},{"x":0.03912353515625,"y":0.17083740234375},{"x":0.14947509765625,"y":-0.401519775390625},{"x":-0.12353515625,"y":-0.039581298828125},{"x":-0.17437744140625,"y":0.00299072265625},{"x":-0.0914306640625,"y":0.1874237060546875},{"x":-0.2296142578125,"y":0.0728607177734375},{"x":-0.279296875,"y":-0.278778076171875},{"x":-0.0740966796875,"y":-0.0958251953125},{"x":0.19189453125,"y":0.1553955078125},{"x":-0.0697021484375,"y":-0.110504150390625},{"x":-0.12384033203125,"y":0.0946044921875},{"x":-0.17388916015625,"y":0.14666748046875},{"x":-0.22802734375,"y":0.4242401123046875}],"optimisedCameraToObject":{"translation":{"x":-0.0324010361421942,"y":0.08646866121733729,"z":0.3190390816377538},"rotation":{"quaternion":{"W":0.6982372867691556,"X":0.04489568943492578,"Y":-0.11185480699789213,"Z":-0.7056469163731072}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":261.5584411621094,"y":431.34576416015625},{"x":260.7383728027344,"y":373.4093322753906},{"x":259.82733154296875,"y":316.7984313964844},{"x":258.5391845703125,"y":260.98419189453125},{"x":257.5627136230469,"y":206.04525756835938},{"x":256.3836669921875,"y":151.73309326171875},{"x":254.87864685058594,"y":98.69119262695312},{"x":320.3822937011719,"y":428.1896057128906},{"x":318.8409729003906,"y":371.04681396484375},{"x":317.3576354980469,"y":315.0987854003906},{"x":315.18621826171875,"y":260.1986083984375},{"x":313.7029113769531,"y":206.84934997558594},{"x":312.06329345703125,"y":153.3551788330078},{"x":310.3150329589844,"y":101.53817749023438},{"x":376.06988525390625,"y":425.09332275390625},{"x":373.8013000488281,"y":368.892578125},{"x":372.1345520019531,"y":314.4423522949219},{"x":370.0775451660156,"y":260.1603088378906},{"x":367.86456298828125,"y":207.4055938720703},{"x":365.8185119628906,"y":154.97972106933594},{"x":364.0362243652344,"y":103.73982238769531},{"x":430.28863525390625,"y":422.14117431640625},{"x":427.94439697265625,"y":366.7496337890625},{"x":425.724609375,"y":312.9056396484375},{"x":423.025390625,"y":260.0701599121094},{"x":420.5255432128906,"y":207.84007263183594},{"x":418.148681640625,"y":156.28213500976562},{"x":415.8549499511719,"y":105.80104064941406},{"x":482.9880065917969,"y":419.21710205078125},{"x":479.9949645996094,"y":364.8000183105469},{"x":476.8944091796875,"y":311.9417419433594},{"x":473.8868103027344,"y":259.6905517578125},{"x":471.17724609375,"y":208.27713012695312},{"x":468.5673828125,"y":157.70179748535156},{"x":466.0921325683594,"y":107.9992446899414},{"x":534.2749633789062,"y":416.22418212890625},{"x":530.6543579101562,"y":362.6839294433594},{"x":527.4532470703125,"y":310.6744384765625},{"x":523.982666015625,"y":259.13385009765625},{"x":520.3619995117188,"y":209.1534423828125},{"x":517.993408203125,"y":158.79196166992188},{"x":514.6072387695312,"y":109.77139282226562},{"x":583.6536254882812,"y":413.9046325683594},{"x":579.3583984375,"y":361.0617980957031},{"x":575.7703247070312,"y":309.47711181640625},{"x":571.8079833984375,"y":259.00164794921875},{"x":568.2830200195312,"y":208.95237731933594},{"x":565.0867919921875,"y":160.04856872558594},{"x":562.015625,"y":111.36634826660156}],"reprojectionErrors":[{"x":0.34954833984375,"y":0.263885498046875},{"x":0.05670166015625,"y":0.206878662109375},{"x":-0.1246337890625,"y":-0.09173583984375},{"x":0.091064453125,"y":-0.138580322265625},{"x":0.014312744140625,"y":-0.0462646484375},{"x":0.158782958984375,"y":0.4012451171875},{"x":0.647247314453125,"y":0.5292129516601562},{"x":-0.380157470703125,"y":0.143951416015625},{"x":-0.472686767578125,"y":0.3095703125},{"x":-0.591644287109375,"y":0.327301025390625},{"x":0.008087158203125,"y":0.310302734375},{"x":-0.0506591796875,"y":-0.27685546875},{"x":0.0755615234375,"y":0.2306365966796875},{"x":0.3382568359375,"y":-0.0190582275390625},{"x":0.071990966796875,"y":0.076446533203125},{"x":0.220916748046875,"y":0.2784423828125},{"x":-0.1904296875,"y":-0.258270263671875},{"x":-0.1712646484375,"y":0.01654052734375},{"x":0.04290771484375,"y":-0.2872314453125},{"x":0.12799072265625,"y":-6.40869140625E-4},{"x":-0.014068603515625,"y":-0.00928497314453125},{"x":0.143890380859375,"y":-0.028961181640625},{"x":-0.084930419921875,"y":0.3065185546875},{"x":-0.3875732421875,"y":0.073028564453125},{"x":-0.1617431640625,"y":-0.221038818359375},{"x":-0.087799072265625,"y":-0.202056884765625},{"x":-0.0906982421875,"y":0.0349273681640625},{"x":-0.132049560546875,"y":0.05805206298828125},{"x":-0.01593017578125,"y":-0.061798095703125},{"x":-0.01934814453125,"y":0.208038330078125},{"x":0.143463134765625,"y":-0.13385009765625},{"x":0.27032470703125,"y":-0.1650390625},{"x":0.154388427734375,"y":-0.144378662109375},{"x":-0.007659912109375,"y":-0.0992431640625},{"x":-0.252288818359375,"y":-0.09033203125},{"x":-0.42315673828125,"y":0.069580078125},{"x":-0.19482421875,"y":0.33935546875},{"x":-0.31988525390625,"y":-0.00445556640625},{"x":-0.11126708984375,"y":0.071929931640625},{"x":0.3096923828125,"y":-0.549652099609375},{"x":-0.46099853515625,"y":0.046142578125},{"x":-0.155517578125,"y":0.11244964599609375},{"x":-0.4969482421875,"y":-0.381927490234375},{"x":0.03582763671875,"y":0.03680419921875},{"x":-0.0657958984375,"y":0.08612060546875},{"x":0.27752685546875,"y":-0.1119384765625},{"x":0.25213623046875,"y":0.0998992919921875},{"x":-0.035400390625,"y":-0.02239990234375},{"x":-0.38336181640625,"y":0.42115020751953125}],"optimisedCameraToObject":{"translation":{"x":-0.08943094831800198,"y":0.0808260788695022,"z":0.2935634462691125},"rotation":{"quaternion":{"W":0.6906661760122009,"X":0.031456948581387284,"Y":-0.1140140801900534,"Z":-0.7134363904491047}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":112.43693542480469,"y":435.12628173828125},{"x":112.2218017578125,"y":376.79998779296875},{"x":111.814453125,"y":319.747314453125},{"x":111.45684051513672,"y":264.0132141113281},{"x":110.68099975585938,"y":210.06393432617188},{"x":110.0819091796875,"y":157.5027618408203},{"x":109.3060531616211,"y":106.29694366455078},{"x":175.11749267578125,"y":429.87091064453125},{"x":173.62478637695312,"y":372.38238525390625},{"x":172.67283630371094,"y":316.74871826171875},{"x":171.37600708007812,"y":262.7649841308594},{"x":169.55967712402344,"y":209.7856903076172},{"x":168.47434997558594,"y":158.04342651367188},{"x":166.60049438476562,"y":107.71265411376953},{"x":234.8468780517578,"y":425.515625},{"x":232.3966522216797,"y":368.8697204589844},{"x":230.2808074951172,"y":314.39923095703125},{"x":228.2808380126953,"y":260.9765930175781},{"x":226.6815185546875,"y":209.38327026367188},{"x":223.88523864746094,"y":158.1434326171875},{"x":221.77545166015625,"y":108.81288146972656},{"x":292.0135192871094,"y":420.4056091308594},{"x":289.1230163574219,"y":365.1078186035156},{"x":286.4530944824219,"y":311.67523193359375},{"x":283.7879333496094,"y":259.75152587890625},{"x":280.75006103515625,"y":208.42861938476562},{"x":278.2586669921875,"y":158.77224731445312},{"x":275.0998840332031,"y":109.919921875},{"x":346.966064453125,"y":416.1065368652344},{"x":343.6707458496094,"y":361.7760925292969},{"x":339.8814697265625,"y":309.0775146484375},{"x":336.6745910644531,"y":257.97802734375},{"x":333.0892333984375,"y":207.51348876953125},{"x":329.95916748046875,"y":158.70578002929688},{"x":326.9558410644531,"y":111.11041259765625},{"x":400.56646728515625,"y":412.0006103515625},{"x":396.0330810546875,"y":358.23358154296875},{"x":392.1878356933594,"y":307.0007629394531},{"x":388.18865966796875,"y":256.4158935546875},{"x":384.6009216308594,"y":206.9236297607422},{"x":379.84222412109375,"y":158.61514282226562},{"x":376.60614013671875,"y":111.98168182373047},{"x":451.7777099609375,"y":407.6751708984375},{"x":446.6807861328125,"y":355.8739318847656},{"x":442.1518859863281,"y":304.7039794921875},{"x":437.7267761230469,"y":255.0220489501953},{"x":433.0757141113281,"y":206.23056030273438},{"x":428.3516540527344,"y":159.28993225097656},{"x":424.6812744140625,"y":112.57283782958984}],"reprojectionErrors":[{"x":0.914703369140625,"y":0.31146240234375},{"x":0.5541915893554688,"y":-0.155364990234375},{"x":0.3978424072265625,"y":-0.214019775390625},{"x":0.2031402587890625,"y":0.014068603515625},{"x":0.437530517578125,"y":-0.00933837890625},{"x":0.5055389404296875,"y":0.0447845458984375},{"x":0.760223388671875,"y":0.145355224609375},{"x":0.087432861328125,"y":0.554931640625},{"x":0.13299560546875,"y":0.44061279296875},{"x":-0.3240814208984375,"y":0.088104248046875},{"x":-0.3998870849609375,"y":-0.369903564453125},{"x":0.078582763671875,"y":-0.35601806640625},{"x":-0.1406707763671875,"y":-0.16693115234375},{"x":0.460418701171875,"y":-0.03760528564453125},{"x":-0.1326446533203125,"y":0.087432861328125},{"x":0.064208984375,"y":0.2708740234375},{"x":-0.0118865966796875,"y":-0.16571044921875},{"x":-0.1451263427734375,"y":-0.1630859375},{"x":-0.6228179931640625,"y":-0.5671844482421875},{"x":0.1502227783203125,"y":0.0370635986328125},{"x":0.288299560546875,"y":0.03643035888671875},{"x":0.00531005859375,"y":0.552581787109375},{"x":-0.104156494140625,"y":0.48138427734375},{"x":-0.351959228515625,"y":0.042694091796875},{"x":-0.52581787109375,"y":-0.471893310546875},{"x":-0.25164794921875,"y":-0.2154541015625},{"x":-0.451751708984375,"y":-0.3113555908203125},{"x":0.084716796875,"y":0.04833221435546875},{"x":0.2811279296875,"y":0.374298095703125},{"x":-0.11553955078125,"y":0.385223388671875},{"x":0.08258056640625,"y":0.20758056640625},{"x":-0.205169677734375,"y":-0.187286376953125},{"x":-0.021942138671875,"y":0.106781005859375},{"x":-0.205322265625,"y":0.0131378173828125},{"x":-0.43035888671875,"y":-0.0756072998046875},{"x":-0.0484619140625,"y":0.16082763671875},{"x":0.1510009765625,"y":0.6163330078125},{"x":-0.220306396484375,"y":-0.070465087890625},{"x":-0.3251953125,"y":-0.07159423828125},{"x":-0.733673095703125,"y":0.113189697265625},{"x":0.132293701171875,"y":0.3405914306640625},{"x":-0.425048828125,"y":0.0700225830078125},{"x":0.16351318359375,"y":0.315948486328125},{"x":0.330474853515625,"y":-0.225372314453125},{"x":0.06158447265625,"y":-0.054656982421875},{"x":-0.184356689453125,"y":-0.0840301513671875},{"x":-0.082763671875,"y":0.231689453125},{"x":0.208587646484375,"y":-0.117523193359375},{"x":-0.441619873046875,"y":0.44864654541015625}],"optimisedCameraToObject":{"translation":{"x":-0.15119806703374591,"y":0.08179878001895687,"z":0.28603371204394046},"rotation":{"quaternion":{"W":0.6763867823871308,"X":0.01566863155479982,"Y":-0.1434175003572894,"Z":-0.7222789178623803}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":462.697265625,"y":446.17315673828125},{"x":458.58038330078125,"y":406.01605224609375},{"x":454.372802734375,"y":365.956298828125},{"x":450.1450500488281,"y":325.9808654785156},{"x":446.0995788574219,"y":286.54705810546875},{"x":442.1083984375,"y":246.5204620361328},{"x":438.0097961425781,"y":207.49322509765625},{"x":495.0740966796875,"y":448.1979675292969},{"x":491.027099609375,"y":406.3558349609375},{"x":486.3382873535156,"y":364.84710693359375},{"x":481.99896240234375,"y":323.3812255859375},{"x":477.5999755859375,"y":282.3045349121094},{"x":473.5657958984375,"y":240.42507934570312},{"x":469.2619323730469,"y":199.7630157470703},{"x":529.9552612304688,"y":450.3905029296875},{"x":525.632080078125,"y":406.95361328125},{"x":521.0580444335938,"y":363.5746765136719},{"x":516.1622314453125,"y":319.9472351074219},{"x":512.0118408203125,"y":277.18408203125},{"x":507.05377197265625,"y":234.00148010253906},{"x":503.0104064941406,"y":191.01577758789062},{"x":568.6978149414062,"y":453.3684387207031},{"x":564.045654296875,"y":407.6001892089844},{"x":558.8128051757812,"y":362.2152099609375},{"x":553.6875610351562,"y":316.3111267089844},{"x":549.1873779296875,"y":271.87200927734375},{"x":544.1602783203125,"y":226.50657653808594},{"x":539.6306762695312,"y":181.8695068359375},{"x":610.7796630859375,"y":456.19268798828125},{"x":605.6180419921875,"y":408.0647888183594},{"x":599.9807739257812,"y":360.35272216796875},{"x":595.07958984375,"y":313.18035888671875},{"x":590.002197265625,"y":265.8324279785156},{"x":584.7716064453125,"y":218.773681640625},{"x":579.861328125,"y":171.21275329589844},{"x":657.2819213867188,"y":459.7998046875},{"x":651.7996826171875,"y":408.9311218261719},{"x":646.0870971679688,"y":358.99554443359375},{"x":640.7421875,"y":308.84881591796875},{"x":635.1204223632812,"y":259.1421813964844},{"x":629.7100830078125,"y":209.4325714111328},{"x":624.1878051757812,"y":160.60220336914062},{"x":708.5916748046875,"y":462.8615417480469},{"x":702.8409423828125,"y":409.9972229003906},{"x":696.6349487304688,"y":357.0209655761719},{"x":690.96630859375,"y":304.0125732421875},{"x":684.7152709960938,"y":251.77542114257812},{"x":679.0584106445312,"y":200.19496154785156},{"x":673.8428955078125,"y":147.28500366210938}],"reprojectionErrors":[{"x":0.1173095703125,"y":0.0916748046875},{"x":0.098968505859375,"y":0.131011962890625},{"x":0.1719970703125,"y":0.180267333984375},{"x":0.265716552734375,"y":0.249969482421875},{"x":0.177398681640625,"y":-0.119537353515625},{"x":0.03485107421875,"y":0.2037353515625},{"x":-4.2724609375E-4,"y":-0.3747100830078125},{"x":0.121734619140625,"y":0.202362060546875},{"x":-0.183837890625,"y":0.245697021484375},{"x":0.154296875,"y":0.0718994140625},{"x":0.14459228515625,"y":-0.031097412109375},{"x":0.1959228515625,"y":-0.41229248046875},{"x":-0.116363525390625,"y":0.11767578125},{"x":-0.158050537109375,"y":-0.4639434814453125},{"x":0.4375,"y":0.337860107421875},{"x":0.16766357421875,"y":0.14654541015625},{"x":0.15191650390625,"y":0.023834228515625},{"x":0.46099853515625,"y":0.273284912109375},{"x":0.02740478515625,"y":-0.2208251953125},{"x":0.403961181640625,"y":-0.17755126953125},{"x":-0.1319580078125,"y":-0.2161102294921875},{"x":0.0972900390625,"y":-0.092864990234375},{"x":-0.1109619140625,"y":0.04888916015625},{"x":0.26641845703125,"y":-0.054351806640625},{"x":0.54083251953125,"y":0.49658203125},{"x":0.19451904296875,"y":-0.28558349609375},{"x":0.37921142578125,"y":-0.012664794921875},{"x":0.0701904296875,"y":-0.342498779296875},{"x":0.08837890625,"y":-0.11895751953125},{"x":0.09063720703125,"y":0.190765380859375},{"x":0.57550048828125,"y":0.236358642578125},{"x":0.3309326171875,"y":-0.10955810546875},{"x":0.268798828125,"y":-0.135284423828125},{"x":0.36578369140625,"y":-0.3090362548828125},{"x":0.14813232421875,"y":0.1571044921875},{"x":-0.1107177734375,"y":-0.638702392578125},{"x":-0.1240234375,"y":-0.002777099609375},{"x":0.1024169921875,"y":-0.132720947265625},{"x":-0.02984619140625,"y":0.111785888671875},{"x":0.123291015625,"y":0.0755615234375},{"x":0.0732421875,"y":0.19781494140625},{"x":0.1429443359375,"y":-0.40753173828125},{"x":-0.20745849609375,"y":-0.277374267578125},{"x":-0.33282470703125,"y":-0.319122314453125},{"x":0.00933837890625,"y":-0.063629150390625},{"x":-0.1739501953125,"y":0.4049072265625},{"x":0.23651123046875,"y":0.278656005859375},{"x":0.06378173828125,"y":-0.3321075439453125},{"x":-0.53973388671875,"y":0.554473876953125}],"optimisedCameraToObject":{"translation":{"x":0.01673757552633122,"y":0.11599505416921317,"z":0.4504946464915309},"rotation":{"quaternion":{"W":0.619510459828121,"X":-0.25547922971352294,"Y":0.2678014256875606,"Z":-0.6922568524386341}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":355.6859436035156,"y":427.2597351074219},{"x":355.3895568847656,"y":385.3179931640625},{"x":355.1605224609375,"y":342.73455810546875},{"x":355.0921630859375,"y":300.2269287109375},{"x":354.9281921386719,"y":257.17108154296875},{"x":354.6838684082031,"y":213.74407958984375},{"x":354.6878356933594,"y":170.0345001220703},{"x":391.8318786621094,"y":432.4383850097656},{"x":391.5391540527344,"y":389.2532653808594},{"x":391.3835144042969,"y":345.7039794921875},{"x":391.3134460449219,"y":301.122314453125},{"x":391.3796081542969,"y":257.0061340332031},{"x":391.1878356933594,"y":212.11300659179688},{"x":391.0421142578125,"y":166.67181396484375},{"x":429.3434753417969,"y":438.40496826171875},{"x":429.6341857910156,"y":393.59930419921875},{"x":429.7971496582031,"y":348.7086486816406},{"x":429.8144836425781,"y":302.9778137207031},{"x":430.002197265625,"y":257.07342529296875},{"x":430.0115966796875,"y":210.10655212402344},{"x":430.1455078125,"y":163.72430419921875},{"x":470.3917541503906,"y":444.7640380859375},{"x":470.5439147949219,"y":398.237060546875},{"x":470.8669738769531,"y":351.4297790527344},{"x":470.9769287109375,"y":303.9964904785156},{"x":471.10455322265625,"y":256.94873046875},{"x":471.6968688964844,"y":208.21885681152344},{"x":471.8651428222656,"y":160.1185760498047},{"x":514.0340576171875,"y":451.9403991699219},{"x":514.1963500976562,"y":403.6577453613281},{"x":514.8700561523438,"y":354.7900390625},{"x":515.305419921875,"y":305.9344787597656},{"x":516.0093383789062,"y":256.4881591796875},{"x":516.117431640625,"y":206.41790771484375},{"x":516.9278564453125,"y":155.85438537597656},{"x":561.2431640625,"y":459.2222900390625},{"x":562.06201171875,"y":408.96051025390625},{"x":562.720703125,"y":358.4737243652344},{"x":563.5679321289062,"y":307.6607666015625},{"x":564.1778564453125,"y":256.186279296875},{"x":564.958984375,"y":203.79953002929688},{"x":565.5916748046875,"y":151.92578125},{"x":612.2916259765625,"y":466.9968566894531},{"x":613.0962524414062,"y":414.9391784667969},{"x":613.697265625,"y":361.8299255371094},{"x":614.9462890625,"y":309.2750549316406},{"x":616.107177734375,"y":255.7460174560547},{"x":617.0111083984375,"y":201.81402587890625},{"x":618.560791015625,"y":146.8963165283203}],"reprojectionErrors":[{"x":0.23577880859375,"y":0.0711669921875},{"x":0.347808837890625,"y":-0.048553466796875},{"x":0.381072998046875,"y":0.1463623046875},{"x":0.2420654296875,"y":-0.06817626953125},{"x":0.186920166015625,"y":-0.0748291015625},{"x":0.200225830078125,"y":-0.05755615234375},{"x":-0.046783447265625,"y":-0.1119232177734375},{"x":-0.269744873046875,"y":0.356201171875},{"x":-0.024139404296875,"y":0.10394287109375},{"x":0.074462890625,"y":-0.13323974609375},{"x":0.077423095703125,"y":0.3057861328125},{"x":-0.066009521484375,"y":-0.084197998046875},{"x":0.03814697265625,"y":-0.06817626953125},{"x":0.0858154296875,"y":0.117279052734375},{"x":0.28497314453125,"y":0.233795166015625},{"x":0.103912353515625,"y":0.131439208984375},{"x":0.042510986328125,"y":-0.259246826171875},{"x":0.1185302734375,"y":-0.19091796875},{"x":0.015869140625,"y":-0.338134765625},{"x":0.0831298828125,"y":0.1798248291015625},{"x":0.01739501953125,"y":-0.29248046875},{"x":-0.008544921875,"y":0.1405029296875},{"x":0.12847900390625,"y":0.184112548828125},{"x":0.088714599609375,"y":0.107696533203125},{"x":0.256134033203125,"y":0.248504638671875},{"x":0.39990234375,"y":-0.413818359375},{"x":0.072906494140625,"y":0.1794281005859375},{"x":0.163848876953125,"y":-0.2926483154296875},{"x":0.09423828125,"y":-0.301116943359375},{"x":0.42730712890625,"y":-0.193603515625},{"x":0.245849609375,"y":0.068695068359375},{"x":0.29949951171875,"y":-0.120819091796875},{"x":0.0814208984375,"y":-0.168914794921875},{"x":0.45599365234375,"y":-0.0522613525390625},{"x":0.125,"y":0.088348388671875},{"x":-0.03076171875,"y":-0.32464599609375},{"x":-0.1165771484375,"y":-0.059478759765625},{"x":-0.04217529296875,"y":-0.033111572265625},{"x":-0.1561279296875,"y":-0.15478515625},{"x":-0.0325927734375,"y":-0.099822998046875},{"x":-0.07989501953125,"y":0.3716888427734375},{"x":0.02154541015625,"y":-0.1768035888671875},{"x":-0.250732421875,"y":-0.25372314453125},{"x":-0.04766845703125,"y":-0.15936279296875},{"x":0.36322021484375,"y":0.48504638671875},{"x":0.13031005859375,"y":0.062103271484375},{"x":-0.01007080078125,"y":0.088470458984375},{"x":0.111083984375,"y":-0.0191497802734375},{"x":-0.4088134765625,"y":0.309539794921875}],"optimisedCameraToObject":{"translation":{"x":-0.05492043538570005,"y":0.09696384131948622,"z":0.4254147432218969},"rotation":{"quaternion":{"W":0.6866393333107599,"X":-0.16938002997694102,"Y":0.21248708229817198,"Z":-0.6743041385398547}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":410.2142333984375,"y":375.68890380859375},{"x":409.99859619140625,"y":336.1283874511719},{"x":409.39190673828125,"y":296.52313232421875},{"x":408.912109375,"y":255.99208068847656},{"x":408.07696533203125,"y":215.76806640625},{"x":407.4430847167969,"y":174.92005920410156},{"x":406.8189697265625,"y":133.39886474609375},{"x":439.0667419433594,"y":380.5579833984375},{"x":438.5921936035156,"y":339.1120910644531},{"x":437.9965515136719,"y":297.85809326171875},{"x":437.59539794921875,"y":255.85430908203125},{"x":437.1660461425781,"y":213.54002380371094},{"x":436.64544677734375,"y":170.54083251953125},{"x":436.0671081542969,"y":127.33467864990234},{"x":469.990966796875,"y":385.89117431640625},{"x":469.78082275390625,"y":342.4855651855469},{"x":469.10528564453125,"y":299.04986572265625},{"x":468.8797912597656,"y":255.30616760253906},{"x":468.6265563964844,"y":211.37200927734375},{"x":468.0635986328125,"y":166.23072814941406},{"x":467.9852294921875,"y":120.9878158569336},{"x":503.97979736328125,"y":391.53900146484375},{"x":503.9522399902344,"y":346.5003662109375},{"x":503.859619140625,"y":300.8630676269531},{"x":503.5802307128906,"y":254.97682189941406},{"x":503.2533874511719,"y":208.51072692871094},{"x":503.1067199707031,"y":161.16571044921875},{"x":502.9981994628906,"y":113.65512084960938},{"x":541.3051147460938,"y":398.0053405761719},{"x":541.3599243164062,"y":350.6518249511719},{"x":541.3790893554688,"y":302.91943359375},{"x":541.2615356445312,"y":254.26646423339844},{"x":541.0132446289062,"y":204.94775390625},{"x":541.2647094726562,"y":155.8580322265625},{"x":541.4986572265625,"y":105.41653442382812},{"x":583.1219482421875,"y":405.11865234375},{"x":583.07568359375,"y":354.9351501464844},{"x":583.375244140625,"y":304.8016357421875},{"x":583.6677856445312,"y":253.30581665039062},{"x":583.845947265625,"y":202.08047485351562},{"x":584.2417602539062,"y":149.39927673339844},{"x":584.5357055664062,"y":96.91033172607422},{"x":629.2529296875,"y":413.1878967285156},{"x":629.7451782226562,"y":360.1501770019531},{"x":630.2662353515625,"y":306.9233093261719},{"x":630.4746704101562,"y":252.96826171875},{"x":631.159423828125,"y":198.0891876220703},{"x":631.721923828125,"y":142.8073272705078},{"x":632.6470336914062,"y":86.31974029541016}],"reprojectionErrors":[{"x":0.3406982421875,"y":0.15643310546875},{"x":0.023681640625,"y":0.149566650390625},{"x":0.0816650390625,"y":-0.140411376953125},{"x":-0.00347900390625,"y":0.1615447998046875},{"x":0.250244140625,"y":-0.18353271484375},{"x":0.28594970703125,"y":-0.2509307861328125},{"x":0.294921875,"y":0.00213623046875},{"x":-0.0343017578125,"y":0.114501953125},{"x":0.007049560546875,"y":0.267974853515625},{"x":0.154083251953125,"y":-0.12774658203125},{"x":0.09100341796875,"y":-0.13775634765625},{"x":0.040283203125,"y":-0.2082672119140625},{"x":0.064697265625,"y":0.028076171875},{"x":0.130523681640625,"y":0.08606719970703125},{"x":0.11761474609375,"y":0.055999755859375},{"x":0.01495361328125,"y":0.28570556640625},{"x":0.363189697265625,"y":0.154541015625},{"x":0.246673583984375,"y":-0.06719970703125},{"x":0.142974853515625,"y":-0.504913330078125},{"x":0.3338623046875,"y":-0.1499176025390625},{"x":0.0247802734375,"y":-0.11592864990234375},{"x":0.18206787109375,"y":0.195526123046875},{"x":0.042938232421875,"y":-0.00653076171875},{"x":-0.0443115234375,"y":-0.03955078125},{"x":0.041839599609375,"y":-0.2618865966796875},{"x":0.161865234375,"y":-0.3516082763671875},{"x":0.087921142578125,"y":-0.0187225341796875},{"x":-0.038177490234375,"y":0.01407623291015625},{"x":0.34283447265625,"y":0.107666015625},{"x":0.2994384765625,"y":-0.0531005859375},{"x":0.28033447265625,"y":-0.309356689453125},{"x":0.386474609375,"y":-0.1292724609375},{"x":0.611572265625,"y":0.2220611572265625},{"x":0.32513427734375,"y":-0.1605224609375},{"x":0.0440673828125,"y":0.2929840087890625},{"x":-0.0013427734375,"y":0.059356689453125},{"x":0.27447509765625,"y":0.2127685546875},{"x":0.1956787109375,"y":-0.210235595703125},{"x":0.11492919921875,"y":0.191162109375},{"x":0.13946533203125,"y":-0.227630615234375},{"x":-0.06280517578125,"y":0.2476654052734375},{"x":-0.172607421875,"y":-0.0435333251953125},{"x":0.00640869140625,"y":-0.14141845703125},{"x":0.01251220703125,"y":0.067413330078125},{"x":-0.0155029296875,"y":-0.122283935546875},{"x":0.263671875,"y":-0.184814453125},{"x":0.06109619140625,"y":0.061920166015625},{"x":-0.02471923828125,"y":0.0825958251953125},{"x":-0.478759765625,"y":0.665618896484375}],"optimisedCameraToObject":{"translation":{"x":-0.017634545972978852,"y":0.06868354041243943,"z":0.4583225750303228},"rotation":{"quaternion":{"W":0.6542121294357013,"X":-0.255133737517321,"Y":0.3055060236541039,"Z":-0.6431013413068783}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":299.2911071777344,"y":503.0108337402344},{"x":292.4292297363281,"y":441.0529479980469},{"x":285.78265380859375,"y":384.1677551269531},{"x":279.81658935546875,"y":330.73583984375},{"x":273.8914489746094,"y":281.0858459472656},{"x":268.2467346191406,"y":234.1954345703125},{"x":263.24371337890625,"y":190.4412841796875},{"x":362.20330810546875,"y":492.14031982421875},{"x":352.87359619140625,"y":431.090576171875},{"x":344.6040954589844,"y":374.8567199707031},{"x":336.2720947265625,"y":322.6497802734375},{"x":328.87982177734375,"y":273.7012634277344},{"x":321.2600402832031,"y":227.7710723876953},{"x":315.127685546875,"y":184.7503662109375},{"x":423.17108154296875,"y":481.1456604003906},{"x":411.8390197753906,"y":421.55963134765625},{"x":400.95989990234375,"y":366.52685546875},{"x":391.3080139160156,"y":315.2815856933594},{"x":382.2103576660156,"y":266.94415283203125},{"x":373.2048645019531,"y":221.78782653808594},{"x":365.1521911621094,"y":179.04685974121094},{"x":482.7032775878906,"y":470.9375305175781},{"x":468.8664245605469,"y":411.8216552734375},{"x":456.72125244140625,"y":358.6193542480469},{"x":445.2480163574219,"y":307.1010437011719},{"x":434.5079040527344,"y":260.1822204589844},{"x":424.83941650390625,"y":215.25592041015625},{"x":414.9050598144531,"y":173.13331604003906},{"x":540.4755249023438,"y":460.16693115234375},{"x":525.2760620117188,"y":403.0032653808594},{"x":510.70892333984375,"y":349.39410400390625},{"x":498.0203857421875,"y":300.0972900390625},{"x":485.42523193359375,"y":253.07302856445312},{"x":474.07208251953125,"y":209.13922119140625},{"x":463.070556640625,"y":167.66293334960938},{"x":597.67041015625,"y":450.3277282714844},{"x":580.2250366210938,"y":393.6614074707031},{"x":564.6302490234375,"y":341.2954406738281},{"x":549.6426391601562,"y":292.1555480957031},{"x":536.0784912109375,"y":246.24392700195312},{"x":523.0137939453125,"y":202.9351806640625},{"x":510.90399169921875,"y":162.03675842285156},{"x":652.9065551757812,"y":440.4656066894531},{"x":634.3095703125,"y":385.3006896972656},{"x":616.8862915039062,"y":333.4922790527344},{"x":600.608154296875,"y":285.2835998535156},{"x":585.046142578125,"y":239.73077392578125},{"x":570.9019165039062,"y":196.95835876464844},{"x":557.4669799804688,"y":156.59262084960938}],"reprojectionErrors":[{"x":0.203582763671875,"y":-0.032501220703125},{"x":-0.032135009765625,"y":0.44091796875},{"x":0.012176513671875,"y":0.145477294921875},{"x":-0.179473876953125,"y":0.258544921875},{"x":-0.011749267578125,"y":0.067901611328125},{"x":0.2374267578125,"y":0.2615203857421875},{"x":0.173065185546875,"y":0.169830322265625},{"x":-0.19854736328125,"y":-0.237518310546875},{"x":-0.12445068359375,"y":0.468658447265625},{"x":-0.46966552734375,"y":0.533233642578125},{"x":-0.17657470703125,"y":0.3211669921875},{"x":-0.303955078125,"y":0.23248291015625},{"x":0.26605224609375,"y":0.1855926513671875},{"x":-0.224884033203125,"y":0.0070953369140625},{"x":-0.201385498046875,"y":-0.051788330078125},{"x":-0.17718505859375,"y":0.2918701171875},{"x":0.169921875,"y":0.1329345703125},{"x":-0.01226806640625,"y":-0.169830322265625},{"x":-0.11865234375,"y":-0.090911865234375},{"x":0.25360107421875,"y":-0.213348388671875},{"x":0.191650390625,"y":-0.0434112548828125},{"x":-0.247955322265625,"y":-0.3974609375},{"x":0.328277587890625,"y":0.539581298828125},{"x":0.113800048828125,"y":-0.504425048828125},{"x":0.038848876953125,"y":0.309295654296875},{"x":-0.03582763671875,"y":-0.27545166015625},{"x":-0.517059326171875,"y":0.0500030517578125},{"x":-0.12750244140625,"y":0.2120361328125},{"x":0.04840087890625,"y":0.063751220703125},{"x":0.12799072265625,"y":0.076202392578125},{"x":0.59234619140625,"y":0.35382080078125},{"x":0.09515380859375,"y":-0.236785888671875},{"x":0.334381103515625,"y":0.0162353515625},{"x":0.0848388671875,"y":0.00750732421875},{"x":0.169464111328125,"y":0.11669921875},{"x":-0.4361572265625,"y":-0.172271728515625},{"x":0.11822509765625,"y":0.33636474609375},{"x":-0.05322265625,"y":0.256317138671875},{"x":0.18353271484375,"y":0.300811767578125},{"x":-0.08349609375,"y":0.1518707275390625},{"x":-0.01434326171875,"y":0.1576385498046875},{"x":-0.138458251953125,"y":0.2661285400390625},{"x":-0.264404296875,"y":-0.160797119140625},{"x":-0.24664306640625,"y":-0.192626953125},{"x":-0.17779541015625,"y":0.027435302734375},{"x":-0.14727783203125,"y":-0.09124755859375},{"x":0.170654296875,"y":0.0909271240234375},{"x":-0.016357421875,"y":0.18194580078125},{"x":-0.080078125,"y":0.31927490234375}],"optimisedCameraToObject":{"translation":{"x":-0.06527766144089482,"y":0.1053694868733986,"z":0.2622915341442859},"rotation":{"quaternion":{"W":0.6284598619536507,"X":-0.11523134344933798,"Y":-0.18894547628796635,"Z":-0.7456940031878844}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":309.0028991699219,"y":415.4538269042969},{"x":301.6268310546875,"y":358.9978942871094},{"x":293.9208068847656,"y":304.38421630859375},{"x":287.02508544921875,"y":250.26136779785156},{"x":279.49822998046875,"y":197.22479248046875},{"x":272.7017822265625,"y":145.22421264648438},{"x":266.0877380371094,"y":93.98435974121094},{"x":365.2574768066406,"y":407.0369873046875},{"x":357.50836181640625,"y":351.0742492675781},{"x":349.3016052246094,"y":297.70794677734375},{"x":342.3138427734375,"y":243.5601348876953},{"x":334.08758544921875,"y":191.51844787597656},{"x":327.1142578125,"y":139.2807159423828},{"x":319.45269775390625,"y":88.57359313964844},{"x":419.673583984375,"y":397.9599914550781},{"x":411.7469482421875,"y":343.2691345214844},{"x":403.67193603515625,"y":289.62939453125},{"x":395.5227966308594,"y":236.72149658203125},{"x":388.0872497558594,"y":185.0197296142578},{"x":379.6968994140625,"y":133.41380310058594},{"x":372.4565734863281,"y":83.41647338867188},{"x":474.2181091308594,"y":389.39105224609375},{"x":464.8936462402344,"y":335.20208740234375},{"x":456.7041931152344,"y":282.6434631347656},{"x":448.90203857421875,"y":230.07125854492188},{"x":440.0152893066406,"y":178.96995544433594},{"x":431.36968994140625,"y":127.4679183959961},{"x":423.8247985839844,"y":78.1759033203125},{"x":527.4381713867188,"y":381.40887451171875},{"x":518.0070190429688,"y":328.0836486816406},{"x":509.08447265625,"y":275.1150817871094},{"x":500.15521240234375,"y":223.1709442138672},{"x":491.8673400878906,"y":172.21421813964844},{"x":483.0121154785156,"y":121.93359375},{"x":474.3329162597656,"y":72.552001953125},{"x":579.9164428710938,"y":374.0208435058594},{"x":570.1023559570312,"y":320.01397705078125},{"x":560.6857299804688,"y":267.63299560546875},{"x":551.2791748046875,"y":216.42623901367188},{"x":542.4210815429688,"y":166.365478515625},{"x":533.8771362304688,"y":116.13651275634766},{"x":525.001953125,"y":67.1678695678711},{"x":631.2323608398438,"y":365.37127685546875},{"x":621.1959838867188,"y":312.865966796875},{"x":611.1359252929688,"y":260.9737548828125},{"x":601.8287963867188,"y":209.73744201660156},{"x":592.24853515625,"y":159.85617065429688},{"x":583.200927734375,"y":110.46075439453125},{"x":574.05908203125,"y":61.95969772338867}],"reprojectionErrors":[{"x":0.0377197265625,"y":0.059112548828125},{"x":-0.054412841796875,"y":0.55267333984375},{"x":0.317596435546875,"y":0.219512939453125},{"x":0.009185791015625,"y":0.3784332275390625},{"x":0.4576416015625,"y":0.4028167724609375},{"x":0.297454833984375,"y":0.31304931640625},{"x":0.0728759765625,"y":0.35562896728515625},{"x":-0.221923828125,"y":-0.226837158203125},{"x":-0.384735107421875,"y":0.346466064453125},{"x":0.052886962890625,"y":-0.680633544921875},{"x":-0.59033203125,"y":0.0381317138671875},{"x":0.1387939453125,"y":-0.4152984619140625},{"x":-0.25531005859375,"y":0.2321319580078125},{"x":0.164459228515625,"y":0.2257537841796875},{"x":0.372283935546875,"y":0.30120849609375},{"x":-0.04046630859375,"y":0.161346435546875},{"x":-0.15399169921875,"y":-0.052398681640625},{"x":-0.047332763671875,"y":-0.0516204833984375},{"x":-0.51275634765625,"y":-0.340240478515625},{"x":0.113800048828125,"y":0.1636199951171875},{"x":-0.2767333984375,"y":-0.08008575439453125},{"x":-0.112457275390625,"y":0.46966552734375},{"x":0.4605712890625,"y":0.372955322265625},{"x":0.05706787109375,"y":-0.395050048828125},{"x":-0.580169677734375,"y":-0.22052001953125},{"x":0.015960693359375,"y":-0.6168365478515625},{"x":0.51519775390625,"y":0.259979248046875},{"x":0.0535888671875,"y":-0.22750091552734375},{"x":-0.19061279296875,"y":0.194793701171875},{"x":0.0916748046875,"y":-0.23382568359375},{"x":0.031158447265625,"y":-0.07769775390625},{"x":0.13800048828125,"y":-0.033843994140625},{"x":-0.240875244140625,"y":-0.0934906005859375},{"x":0.09857177734375,"y":0.02770233154296875},{"x":0.408416748046875,"y":0.08078765869140625},{"x":-0.41375732421875,"y":-0.535675048828125},{"x":-0.13189697265625,"y":0.23638916015625},{"x":-0.0748291015625,"y":0.306976318359375},{"x":0.13946533203125,"y":0.0991363525390625},{"x":-0.032470703125,"y":-0.386383056640625},{"x":-0.36114501953125,"y":0.13826751708984375},{"x":-0.20599365234375,"y":0.21917724609375},{"x":-0.33135986328125,"y":0.1292724609375},{"x":-0.197265625,"y":-0.093505859375},{"x":0.13970947265625,"y":-0.021453857421875},{"x":-0.10260009765625,"y":0.2747039794921875},{"x":0.0966796875,"y":0.069000244140625},{"x":-0.07330322265625,"y":0.2048797607421875},{"x":0.009521484375,"y":0.24907302856445312}],"optimisedCameraToObject":{"translation":{"x":-0.06721475943916681,"y":0.07760243706458975,"z":0.3030560767255341},"rotation":{"quaternion":{"W":0.6517974545034864,"X":-0.00706054826914844,"Y":-0.07762772257779407,"Z":-0.7543766722588257}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":174.80795288085938,"y":420.4444274902344},{"x":174.94140625,"y":379.3103942871094},{"x":175.08621215820312,"y":336.91827392578125},{"x":174.75804138183594,"y":292.69317626953125},{"x":174.47854614257812,"y":246.8424530029297},{"x":174.19676208496094,"y":199.34597778320312},{"x":173.83421325683594,"y":150.39280700683594},{"x":220.8792266845703,"y":418.94439697265625},{"x":221.7018585205078,"y":377.7818908691406},{"x":222.44631958007812,"y":336.33355712890625},{"x":223.2470245361328,"y":293.00384521484375},{"x":223.88278198242188,"y":248.17918395996094},{"x":224.79437255859375,"y":202.29550170898438},{"x":224.64639282226562,"y":154.33648681640625},{"x":265.2255554199219,"y":416.4397888183594},{"x":266.672607421875,"y":376.6569519042969},{"x":267.77020263671875,"y":335.74505615234375},{"x":269.0673522949219,"y":293.4280700683594},{"x":270.56146240234375,"y":249.66917419433594},{"x":271.9936828613281,"y":204.6778106689453},{"x":273.891845703125,"y":158.02760314941406},{"x":307.9219665527344,"y":414.4686279296875},{"x":309.8504943847656,"y":375.4829406738281},{"x":311.8018798828125,"y":335.4129943847656},{"x":313.4546203613281,"y":293.94873046875},{"x":315.79937744140625,"y":251.24176025390625},{"x":318.0823059082031,"y":206.9315643310547},{"x":320.291015625,"y":160.92413330078125},{"x":348.2652893066406,"y":412.97222900390625},{"x":351.0491027832031,"y":374.25543212890625},{"x":353.3840026855469,"y":334.9397277832031},{"x":355.9903259277344,"y":294.36065673828125},{"x":358.5233459472656,"y":252.02870178222656},{"x":361.7499084472656,"y":209.16329956054688},{"x":364.7424621582031,"y":164.00144958496094},{"x":387.8901062011719,"y":411.0572204589844},{"x":391.4609375,"y":373.6112365722656},{"x":393.9691162109375,"y":334.820556640625},{"x":397.1512756347656,"y":294.8877868652344},{"x":400.343017578125,"y":253.74786376953125},{"x":403.99267578125,"y":210.90695190429688},{"x":407.9291687011719,"y":166.95477294921875},{"x":425.81451416015625,"y":409.3721923828125},{"x":428.97003173828125,"y":372.2181701660156},{"x":432.8382263183594,"y":334.3865661621094},{"x":436.7044372558594,"y":295.1102294921875},{"x":440.78729248046875,"y":254.95220947265625},{"x":445.1363525390625,"y":212.6277313232422},{"x":449.0493469238281,"y":170.06150817871094}],"reprojectionErrors":[{"x":0.6445159912109375,"y":-0.0284423828125},{"x":0.3627471923828125,"y":-0.0557861328125},{"x":0.0640716552734375,"y":-0.225799560546875},{"x":0.2325286865234375,"y":-0.03985595703125},{"x":0.3461456298828125,"y":0.2127685546875},{"x":0.4555206298828125,"y":0.4641265869140625},{"x":0.638763427734375,"y":0.4303436279296875},{"x":0.2110137939453125,"y":-0.556365966796875},{"x":-0.00531005859375,"y":0.2081298828125},{"x":-0.122528076171875,"y":-0.089202880859375},{"x":-0.27392578125,"y":0.075286865234375},{"x":-0.237091064453125,"y":0.2378997802734375},{"x":-0.4515533447265625,"y":-0.1201019287109375},{"x":0.4195098876953125,"y":-0.071533203125},{"x":-0.20068359375,"y":0.007476806640625},{"x":-0.34295654296875,"y":0.1265869140625},{"x":-0.09124755859375,"y":0.077239990234375},{"x":0.007781982421875,"y":0.067413330078125},{"x":-0.040771484375,"y":0.0611114501953125},{"x":0.024627685546875,"y":-0.229156494140625},{"x":-0.321014404296875,"y":-0.4608917236328125},{"x":-0.567413330078125,"y":0.12005615234375},{"x":-0.544036865234375,"y":0.14892578125},{"x":-0.477996826171875,"y":0.011749267578125},{"x":-0.04437255859375,"y":-0.045745849609375},{"x":-0.230255126953125,"y":-0.243927001953125},{"x":-0.277923583984375,"y":-0.2959747314453125},{"x":-0.170867919921875,"y":-0.186859130859375},{"x":-0.095062255859375,"y":-0.16455078125},{"x":-0.32696533203125,"y":0.2763671875},{"x":-0.025665283203125,"y":0.110565185546875},{"x":0.09271240234375,"y":-0.0584716796875},{"x":0.377410888671875,"y":0.1937713623046875},{"x":0.0665283203125,"y":-0.4217681884765625},{"x":0.09271240234375,"y":-0.2166290283203125},{"x":-0.334136962890625,"y":0.042724609375},{"x":-0.79620361328125,"y":-0.130706787109375},{"x":-0.094696044921875,"y":-0.122894287109375},{"x":0.038726806640625,"y":-0.194183349609375},{"x":0.273834228515625,"y":-0.3411102294921875},{"x":0.167999267578125,"y":-0.135650634765625},{"x":-0.10162353515625,"y":-0.2379302978515625},{"x":-0.224639892578125,"y":0.08935546875},{"x":0.2457275390625,"y":0.25714111328125},{"x":0.119171142578125,"y":-0.02093505859375},{"x":0.115997314453125,"y":-0.032562255859375},{"x":0.0235595703125,"y":-0.3991851806640625},{"x":-0.2012939453125,"y":0.1016693115234375},{"x":0.15057373046875,"y":-0.52130126953125}],"optimisedCameraToObject":{"translation":{"x":-0.16252164339136316,"y":0.09025339032546893,"z":0.39489191303495697},"rotation":{"quaternion":{"W":0.708343906982329,"X":0.2024412954796934,"Y":-0.010895954827218099,"Z":-0.6761269921352915}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img11.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":165.51943969726562,"y":436.06866455078125},{"x":158.5010223388672,"y":397.0719299316406},{"x":150.96055603027344,"y":356.7622985839844},{"x":143.713134765625,"y":314.8393859863281},{"x":135.65194702148438,"y":270.9295349121094},{"x":127.2190933227539,"y":225.28134155273438},{"x":118.8882064819336,"y":177.31539916992188},{"x":209.3057861328125,"y":426.20379638671875},{"x":203.6938018798828,"y":387.9049987792969},{"x":197.42996215820312,"y":348.47344970703125},{"x":190.8406219482422,"y":307.0487365722656},{"x":184.0563507080078,"y":264.3448791503906},{"x":177.302490234375,"y":219.41915893554688},{"x":169.59518432617188,"y":172.94454956054688},{"x":251.29010009765625,"y":416.8193359375},{"x":246.50399780273438,"y":379.4416198730469},{"x":241.08248901367188,"y":340.3077392578125},{"x":235.8385772705078,"y":300.123779296875},{"x":230.03819274902344,"y":258.1589660644531},{"x":223.95700073242188,"y":214.39480590820312},{"x":218.00869750976562,"y":168.8299560546875},{"x":291.4856262207031,"y":407.8445739746094},{"x":287.8282470703125,"y":370.99847412109375},{"x":283.1613464355469,"y":333.0888671875},{"x":278.4613952636719,"y":293.2689514160156},{"x":273.8875427246094,"y":252.1122283935547},{"x":268.9695739746094,"y":209.3563232421875},{"x":263.5240173339844,"y":165.0540771484375},{"x":329.74041748046875,"y":399.18011474609375},{"x":326.31341552734375,"y":363.052490234375},{"x":322.85040283203125,"y":325.52886962890625},{"x":319.57342529296875,"y":286.851318359375},{"x":315.089111328125,"y":246.40185546875},{"x":311.6228942871094,"y":204.38320922851562},{"x":306.9957275390625,"y":161.01190185546875},{"x":367.01568603515625,"y":391.22198486328125},{"x":364.3041076660156,"y":355.47369384765625},{"x":361.40069580078125,"y":318.93328857421875},{"x":358.02044677734375,"y":280.47857666015625},{"x":355.6181335449219,"y":241.0682830810547},{"x":352.12750244140625,"y":199.96949768066406},{"x":348.7419128417969,"y":157.72340393066406},{"x":401.9745788574219,"y":383.1734313964844},{"x":400.1711730957031,"y":348.1167297363281},{"x":397.8639831542969,"y":312.1514892578125},{"x":395.63116455078125,"y":274.9392395019531},{"x":393.8119201660156,"y":236.13250732421875},{"x":390.9854431152344,"y":195.97927856445312},{"x":388.6015930175781,"y":153.87838745117188}],"reprojectionErrors":[{"x":0.1148529052734375,"y":-0.27569580078125},{"x":0.18701171875,"y":-0.0748291015625},{"x":0.504791259765625,"y":-0.10479736328125},{"x":0.2357025146484375,"y":-0.16253662109375},{"x":0.4676055908203125,"y":0.02001953125},{"x":0.7378616333007812,"y":0.0793914794921875},{"x":0.5504150390625,"y":0.4698486328125},{"x":0.03515625,"y":-0.1170654296875},{"x":-0.307403564453125,"y":0.0660400390625},{"x":-0.2285003662109375,"y":-0.100372314453125},{"x":-0.0687255859375,"y":0.152862548828125},{"x":0.0260009765625,"y":0.01275634765625},{"x":-0.1863555908203125,"y":0.314605712890625},{"x":0.2598724365234375,"y":0.2686767578125},{"x":-0.1111602783203125,"y":-0.012115478515625},{"x":-0.3663330078125,"y":-0.0928955078125},{"x":-0.17559814453125,"y":0.1580810546875},{"x":-0.363372802734375,"y":-0.05108642578125},{"x":-0.20794677734375,"y":-0.082427978515625},{"x":0.0016326904296875,"y":-0.018035888671875},{"x":-0.162841796875,"y":0.034271240234375},{"x":-0.21575927734375,"y":0.08221435546875},{"x":-0.75750732421875,"y":0.105010986328125},{"x":-0.442840576171875,"y":-0.1785888671875},{"x":-0.257171630859375,"y":-0.002593994140625},{"x":-0.36944580078125,"y":-0.027679443359375},{"x":-0.319976806640625,"y":-0.0858001708984375},{"x":0.063262939453125,"y":-0.3320159912109375},{"x":-0.015380859375,"y":0.239837646484375},{"x":-0.009979248046875,"y":0.158416748046875},{"x":-0.08917236328125,"y":0.1544189453125},{"x":-0.481903076171875,"y":-0.09033203125},{"x":0.1976318359375,"y":-0.0399322509765625},{"x":-0.2840576171875,"y":0.0143585205078125},{"x":0.243255615234375,"y":-0.2398681640625},{"x":-0.369232177734375,"y":0.04150390625},{"x":-0.36053466796875,"y":0.174957275390625},{"x":-0.25152587890625,"y":-0.16961669921875},{"x":0.237518310546875,"y":0.058197021484375},{"x":-0.353668212890625,"y":-0.1776123046875},{"x":0.035064697265625,"y":-0.22747802734375},{"x":0.203948974609375,"y":-0.722564697265625},{"x":0.15325927734375,"y":0.2625732421875},{"x":-0.081024169921875,"y":0.279449462890625},{"x":0.122833251953125,"y":-0.01947021484375},{"x":0.183013916015625,"y":-0.363494873046875},{"x":-0.24359130859375,"y":-0.4781341552734375},{"x":0.259552001953125,"y":-0.6898193359375},{"x":0.23809814453125,"y":-0.482025146484375}],"optimisedCameraToObject":{"translation":{"x":-0.1683410604296514,"y":0.10541666346934725,"z":0.40716621221837446},"rotation":{"quaternion":{"W":0.6456688486875392,"X":0.24234440896970638,"Y":-0.03182764642118764,"Z":-0.7234417227385487}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img12.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":89.08273315429688,"y":375.1281433105469},{"x":102.8569564819336,"y":339.33551025390625},{"x":117.0504379272461,"y":302.9166259765625},{"x":131.8629608154297,"y":265.1017761230469},{"x":146.7024688720703,"y":225.87747192382812},{"x":162.31454467773438,"y":185.2356414794922},{"x":178.23805236816406,"y":143.17184448242188},{"x":120.15544128417969,"y":397.7239685058594},{"x":134.65794372558594,"y":361.8024597167969},{"x":149.70797729492188,"y":325.1379699707031},{"x":164.94393920898438,"y":286.8821105957031},{"x":180.93923950195312,"y":247.65579223632812},{"x":197.20933532714844,"y":206.7247772216797},{"x":214.1441192626953,"y":164.6199493408203},{"x":151.8096923828125,"y":420.72314453125},{"x":166.99453735351562,"y":384.64007568359375},{"x":182.79672241210938,"y":347.7272644042969},{"x":199.13351440429688,"y":309.4944152832031},{"x":215.7339630126953,"y":270.0608215332031},{"x":232.93878173828125,"y":228.89691162109375},{"x":250.70053100585938,"y":186.29986572265625},{"x":184.21875,"y":444.5740661621094},{"x":200.69866943359375,"y":408.38421630859375},{"x":217.10780334472656,"y":371.3687438964844},{"x":234.1734619140625,"y":332.81427001953125},{"x":251.7411346435547,"y":293.0636291503906},{"x":270.0513916015625,"y":251.75888061523438},{"x":288.80963134765625,"y":209.05926513671875},{"x":217.91555786132812,"y":469.0693359375},{"x":234.85226440429688,"y":432.8445739746094},{"x":252.2184600830078,"y":395.45330810546875},{"x":270.0855712890625,"y":356.8077697753906},{"x":288.7647705078125,"y":316.882080078125},{"x":307.8861389160156,"y":275.2120666503906},{"x":327.7116394042969,"y":232.2301025390625},{"x":252.6378173828125,"y":494.47027587890625},{"x":270.3807373046875,"y":458.0096740722656},{"x":288.56085205078125,"y":420.5610656738281},{"x":307.4312438964844,"y":381.54742431640625},{"x":326.97174072265625,"y":341.61016845703125},{"x":347.22149658203125,"y":299.6034851074219},{"x":368.131591796875,"y":256.3837890625},{"x":288.0289001464844,"y":520.5576782226562},{"x":306.7459411621094,"y":483.9833068847656},{"x":325.9294128417969,"y":446.2581481933594},{"x":345.85186767578125,"y":407.1900329589844},{"x":366.1863708496094,"y":366.785400390625},{"x":387.6380920410156,"y":324.8784484863281},{"x":409.78826904296875,"y":281.2734680175781}],"reprojectionErrors":[{"x":0.5576019287109375,"y":-0.0926513671875},{"x":0.451507568359375,"y":0.25750732421875},{"x":0.3664703369140625,"y":0.061248779296875},{"x":0.1259918212890625,"y":0.026336669921875},{"x":0.3470916748046875,"y":0.0998382568359375},{"x":0.3109893798828125,"y":0.2185516357421875},{"x":0.5075836181640625,"y":0.310394287109375},{"x":0.2159881591796875,"y":-0.287078857421875},{"x":0.092742919921875,"y":0.036651611328125},{"x":-0.1063995361328125,"y":-0.0916748046875},{"x":0.0054779052734375,"y":0.112213134765625},{"x":-0.11785888671875,"y":-0.0413055419921875},{"x":0.03729248046875,"y":0.1081390380859375},{"x":0.1124114990234375,"y":-0.0497283935546875},{"x":0.184112548828125,"y":-0.21380615234375},{"x":0.1266021728515625,"y":0.12139892578125},{"x":-0.0430145263671875,"y":0.068389892578125},{"x":-0.2144775390625,"y":0.0511474609375},{"x":-0.0872650146484375,"y":-0.120849609375},{"x":0.0296478271484375,"y":0.005462646484375},{"x":0.21795654296875,"y":0.05047607421875},{"x":0.3326416015625,"y":-0.2882080078125},{"x":-0.23236083984375,"y":0.00970458984375},{"x":-0.185272216796875,"y":-0.10821533203125},{"x":-0.223480224609375,"y":0.002838134765625},{"x":-0.1602783203125,"y":-0.073760986328125},{"x":-0.201629638671875,"y":-0.0594635009765625},{"x":-0.01556396484375,"y":-0.1990814208984375},{"x":0.1754913330078125,"y":-0.267730712890625},{"x":-0.0164337158203125,"y":-0.072113037109375},{"x":-0.0578155517578125,"y":0.02459716796875},{"x":0.012481689453125,"y":0.0390625},{"x":-0.08160400390625,"y":-0.0792236328125},{"x":0.06756591796875,"y":0.051513671875},{"x":0.23883056640625,"y":-0.0899658203125},{"x":0.0249786376953125,"y":-0.3760986328125},{"x":-0.09808349609375,"y":-0.074005126953125},{"x":-0.036590576171875,"y":-0.0738525390625},{"x":-0.00823974609375,"y":0.1278076171875},{"x":0.04541015625,"y":-0.18975830078125},{"x":0.126434326171875,"y":0.033843994140625},{"x":0.328277587890625,"y":-0.1502685546875},{"x":0.291168212890625,"y":-0.35400390625},{"x":0.117584228515625,"y":-0.058563232421875},{"x":0.144195556640625,"y":0.072662353515625},{"x":0.13702392578125,"y":0.1556396484375},{"x":0.4647216796875,"y":0.101654052734375},{"x":0.46710205078125,"y":-0.012237548828125},{"x":0.6116943359375,"y":-0.086395263671875}],"optimisedCameraToObject":{"translation":{"x":-0.22712344574286047,"y":0.0506431465090678,"z":0.4279467072034604},"rotation":{"quaternion":{"W":0.8486889092280236,"X":-0.0360829278793204,"Y":0.17608892519862682,"Z":-0.4974111459259791}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img13.png"},{"locationInObjectSpace":[{"x":0.02539999969303608,"y":0.02539999969303608,"z":0.0},{"x":0.05079999938607216,"y":0.02539999969303608,"z":0.0},{"x":0.07620000094175339,"y":0.02539999969303608,"z":0.0},{"x":0.10159999877214432,"y":0.02539999969303608,"z":0.0},{"x":0.12700000405311584,"y":0.02539999969303608,"z":0.0},{"x":0.15240000188350677,"y":0.02539999969303608,"z":0.0},{"x":0.1777999997138977,"y":0.02539999969303608,"z":0.0},{"x":0.02539999969303608,"y":0.05079999938607216,"z":0.0},{"x":0.05079999938607216,"y":0.05079999938607216,"z":0.0},{"x":0.07620000094175339,"y":0.05079999938607216,"z":0.0},{"x":0.10159999877214432,"y":0.05079999938607216,"z":0.0},{"x":0.12700000405311584,"y":0.05079999938607216,"z":0.0},{"x":0.15240000188350677,"y":0.05079999938607216,"z":0.0},{"x":0.1777999997138977,"y":0.05079999938607216,"z":0.0},{"x":0.02539999969303608,"y":0.07620000094175339,"z":0.0},{"x":0.05079999938607216,"y":0.07620000094175339,"z":0.0},{"x":0.07620000094175339,"y":0.07620000094175339,"z":0.0},{"x":0.10159999877214432,"y":0.07620000094175339,"z":0.0},{"x":0.12700000405311584,"y":0.07620000094175339,"z":0.0},{"x":0.15240000188350677,"y":0.07620000094175339,"z":0.0},{"x":0.1777999997138977,"y":0.07620000094175339,"z":0.0},{"x":0.02539999969303608,"y":0.10159999877214432,"z":0.0},{"x":0.05079999938607216,"y":0.10159999877214432,"z":0.0},{"x":0.07620000094175339,"y":0.10159999877214432,"z":0.0},{"x":0.10159999877214432,"y":0.10159999877214432,"z":0.0},{"x":0.12700000405311584,"y":0.10159999877214432,"z":0.0},{"x":0.15240000188350677,"y":0.10159999877214432,"z":0.0},{"x":0.1777999997138977,"y":0.10159999877214432,"z":0.0},{"x":0.02539999969303608,"y":0.12700000405311584,"z":0.0},{"x":0.05079999938607216,"y":0.12700000405311584,"z":0.0},{"x":0.07620000094175339,"y":0.12700000405311584,"z":0.0},{"x":0.10159999877214432,"y":0.12700000405311584,"z":0.0},{"x":0.12700000405311584,"y":0.12700000405311584,"z":0.0},{"x":0.15240000188350677,"y":0.12700000405311584,"z":0.0},{"x":0.1777999997138977,"y":0.12700000405311584,"z":0.0},{"x":0.02539999969303608,"y":0.15240000188350677,"z":0.0},{"x":0.05079999938607216,"y":0.15240000188350677,"z":0.0},{"x":0.07620000094175339,"y":0.15240000188350677,"z":0.0},{"x":0.10159999877214432,"y":0.15240000188350677,"z":0.0},{"x":0.12700000405311584,"y":0.15240000188350677,"z":0.0},{"x":0.15240000188350677,"y":0.15240000188350677,"z":0.0},{"x":0.1777999997138977,"y":0.15240000188350677,"z":0.0},{"x":0.02539999969303608,"y":0.1777999997138977,"z":0.0},{"x":0.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.10159999877214432,"y":0.1777999997138977,"z":0.0},{"x":0.12700000405311584,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0},{"x":0.1777999997138977,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":390.81396484375,"y":466.0650634765625},{"x":367.743896484375,"y":434.1089172363281},{"x":343.5740661621094,"y":400.4813232421875},{"x":317.9857482910156,"y":365.26812744140625},{"x":291.05438232421875,"y":328.0996398925781},{"x":262.2881164550781,"y":288.5573425292969},{"x":231.9792022705078,"y":246.81471252441406},{"x":410.68243408203125,"y":433.2745056152344},{"x":389.0378112792969,"y":401.93682861328125},{"x":366.5049743652344,"y":369.19757080078125},{"x":342.7806701660156,"y":334.6634216308594},{"x":317.7487487792969,"y":298.3332214355469},{"x":291.0621032714844,"y":259.8555603027344},{"x":262.9956359863281,"y":219.2051239013672},{"x":428.807861328125,"y":403.3410949707031},{"x":408.3904113769531,"y":372.70025634765625},{"x":387.39947509765625,"y":340.51953125},{"x":365.0928649902344,"y":306.8824462890625},{"x":341.8476867675781,"y":271.3581848144531},{"x":317.0367431640625,"y":233.8619384765625},{"x":291.0256652832031,"y":194.30099487304688},{"x":445.7434387207031,"y":375.7165222167969},{"x":426.6754455566406,"y":345.5865478515625},{"x":406.751708984375,"y":314.1173095703125},{"x":385.9114990234375,"y":281.1583251953125},{"x":364.0539855957031,"y":246.49119567871094},{"x":340.9404602050781,"y":209.94944763183594},{"x":316.82183837890625,"y":171.57437133789062},{"x":461.2699279785156,"y":350.19287109375},{"x":443.1463317871094,"y":320.5694580078125},{"x":424.63751220703125,"y":289.78369140625},{"x":404.92498779296875,"y":257.54193115234375},{"x":384.3226013183594,"y":223.75856018066406},{"x":362.8130187988281,"y":188.02833557128906},{"x":340.1267395019531,"y":150.86563110351562},{"x":475.8437194824219,"y":326.29364013671875},{"x":458.88604736328125,"y":297.1778564453125},{"x":441.1073913574219,"y":267.09051513671875},{"x":422.6382751464844,"y":235.62274169921875},{"x":403.2398681640625,"y":202.5699462890625},{"x":383.0358581542969,"y":167.84823608398438},{"x":361.8847961425781,"y":131.3121795654297},{"x":489.09588623046875,"y":304.07415771484375},{"x":473.0478820800781,"y":275.8107604980469},{"x":456.3420715332031,"y":246.29701232910156},{"x":438.8987731933594,"y":215.40675354003906},{"x":420.7943420410156,"y":183.17337036132812},{"x":401.6164245605469,"y":149.00538635253906},{"x":381.53302001953125,"y":113.80071258544922}],"reprojectionErrors":[{"x":-0.23974609375,"y":-0.062164306640625},{"x":-0.180267333984375,"y":0.08905029296875},{"x":-0.230316162109375,"y":0.221282958984375},{"x":-0.171478271484375,"y":0.1083984375},{"x":-0.19097900390625,"y":-0.03607177734375},{"x":0.078216552734375,"y":0.0318603515625},{"x":0.20391845703125,"y":-0.0568084716796875},{"x":-0.29150390625,"y":0.16204833984375},{"x":-0.187835693359375,"y":0.241058349609375},{"x":-0.2774658203125,"y":0.132171630859375},{"x":-0.342864990234375,"y":0.102630615234375},{"x":-0.363006591796875,"y":0.013885498046875},{"x":-0.09649658203125,"y":0.06201171875},{"x":0.063934326171875,"y":0.0991668701171875},{"x":-0.159515380859375,"y":0.12335205078125},{"x":0.029144287109375,"y":0.06805419921875},{"x":-0.18084716796875,"y":0.05645751953125},{"x":-0.12109375,"y":-0.108551025390625},{"x":-0.250274658203125,"y":-0.12164306640625},{"x":-0.031341552734375,"y":-0.0367584228515625},{"x":0.069976806640625,"y":0.08477783203125},{"x":-0.216461181640625,"y":0.069732666015625},{"x":-0.199859619140625,"y":0.07366943359375},{"x":-0.20538330078125,"y":0.00689697265625},{"x":-0.23626708984375,"y":-0.0828857421875},{"x":-0.26202392578125,"y":-0.090240478515625},{"x":-0.121490478515625,"y":0.026824951171875},{"x":-0.1512451171875,"y":0.089447021484375},{"x":-0.089447021484375,"y":-0.046478271484375},{"x":0.044097900390625,"y":0.022125244140625},{"x":-0.233245849609375,"y":-0.07733154296875},{"x":-0.158782958984375,"y":-0.144378662109375},{"x":-0.107421875,"y":-0.195465087890625},{"x":-0.128936767578125,"y":0.06256103515625},{"x":-0.02764892578125,"y":-0.0080108642578125},{"x":-0.103179931640625,"y":0.03216552734375},{"x":-0.1748046875,"y":0.1607666015625},{"x":-0.150238037109375,"y":0.0040283203125},{"x":-0.20892333984375,"y":-0.1138763427734375},{"x":-0.1654052734375,"y":-0.080902099609375},{"x":-0.20172119140625,"y":0.0856170654296875},{"x":-0.240478515625,"y":0.42010498046875},{"x":0.224700927734375,"y":0.061614990234375},{"x":0.116546630859375,"y":-0.101593017578125},{"x":0.00390625,"y":-0.2033538818359375},{"x":-0.07659912109375,"y":-0.19476318359375},{"x":-0.24822998046875,"y":-0.1933441162109375},{"x":-0.149688720703125,"y":0.3006591796875},{"x":-0.0048828125,"y":0.289093017578125}],"optimisedCameraToObject":{"translation":{"x":-0.010560150704256737,"y":0.12578530870683613,"z":0.3821128035823055},"rotation":{"quaternion":{"W":0.3703113990308617,"X":0.3444073258617158,"Y":-0.24653226908564677,"Z":-0.8267254090325699}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/ffe9e294-b625-43bc-ae61-8c165a2028a3/imgs/800x600/img14.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file