From 3d71b6236d9319c0dfbabae9a69a8a96ba3a2b03 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Sun, 7 Dec 2025 11:42:40 -0500 Subject: [PATCH 1/7] changing how the photon classes work --- src/main/java/org/team2342/frc/Constants.java | 42 +- .../java/org/team2342/frc/RobotContainer.java | 24 +- .../team2342/frc/subsystems/drive/Drive.java | 6 + .../frc/subsystems/vision/Vision.java | 17 +- .../frc/subsystems/vision/VisionIO.java | 3 +- .../vision/VisionIOConstrainedSim.java | 62 --- .../frc/subsystems/vision/VisionIOPhoton.java | 146 ++++--- .../vision/VisionIOPhotonConstrained.java | 409 ------------------ .../frc/subsystems/vision/VisionIOSim.java | 16 +- .../org/team2342/lib/util/Timestamped.java | 28 ++ 10 files changed, 204 insertions(+), 549 deletions(-) delete mode 100644 src/main/java/org/team2342/frc/subsystems/vision/VisionIOConstrainedSim.java delete mode 100644 src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhotonConstrained.java create mode 100644 src/main/java/org/team2342/lib/util/Timestamped.java diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index ab975ed..824e2c9 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -8,10 +8,19 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.MatBuilder; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.Nat; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.math.numbers.N8; import edu.wpi.first.math.util.Units; +import java.util.Optional; +import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; +import org.team2342.frc.subsystems.vision.VisionIOPhoton.CameraParameters; public final class Constants { public static final Mode CURRENT_MODE = Mode.SIM; @@ -50,8 +59,37 @@ public static final class VisionConstants { // The layout of the AprilTags on the field public static final AprilTagFieldLayout TAG_LAYOUT = - AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark); - + AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded); + + public static final Matrix cameraMatrix = + MatBuilder.fill( + Nat.N3(), + Nat.N3(), + 680.3518437477294, + 0.0, + 393.34429560711095, + 0.0, + 681.5148816063638, + 304.5111454902841, + 0.0, + 0.0, + 1.0); + public static final Matrix distCoeffs = + MatBuilder.fill( + Nat.N8(), + Nat.N1(), + 0.04913279370181987, + -0.08080811604393605, + 0.0012713783068216294, + -9.086414571538155E-4, + 0.03813939624862079, + -0.002083234186226857, + 0.003667258530403619, + -0.0014957440403602612); + public static final CameraParameters PARAMETERS = + new CameraParameters(cameraMatrix, distCoeffs); + public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = + Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; public static final double MAX_Z_ERROR = 0.75; diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index c61e90b..bb4b25f 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -23,6 +23,7 @@ import lombok.Getter; import org.littletonrobotics.junction.inputs.LoggedPowerDistribution; import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; +import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.team2342.frc.Constants.CANConstants; import org.team2342.frc.Constants.DriveConstants; import org.team2342.frc.Constants.VisionConstants; @@ -63,10 +64,17 @@ public RobotContainer() { vision = new Vision( drive::addVisionMeasurement, + drive::getTimestampedHeading, new VisionIOPhoton( - VisionConstants.RIGHT_CAMERA_NAME, VisionConstants.FRONT_RIGHT_TRANSFORM), + VisionConstants.RIGHT_CAMERA_NAME, + VisionConstants.PARAMETERS, + PoseStrategy.CONSTRAINED_SOLVEPNP, + VisionConstants.FRONT_RIGHT_TRANSFORM), new VisionIOPhoton( - VisionConstants.LEFT_CAMERA_NAME, VisionConstants.FRONT_LEFT_TRANSFORM)); + VisionConstants.LEFT_CAMERA_NAME, + VisionConstants.PARAMETERS, + PoseStrategy.CONSTRAINED_SOLVEPNP, + VisionConstants.FRONT_LEFT_TRANSFORM)); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); break; @@ -82,12 +90,17 @@ public RobotContainer() { vision = new Vision( drive::addVisionMeasurement, + drive::getTimestampedHeading, new VisionIOSim( VisionConstants.RIGHT_CAMERA_NAME, + VisionConstants.PARAMETERS, + PoseStrategy.PNP_DISTANCE_TRIG_SOLVE, VisionConstants.FRONT_RIGHT_TRANSFORM, drive::getRawOdometryPose), new VisionIOSim( VisionConstants.LEFT_CAMERA_NAME, + VisionConstants.PARAMETERS, + PoseStrategy.PNP_DISTANCE_TRIG_SOLVE, VisionConstants.FRONT_LEFT_TRANSFORM, drive::getRawOdometryPose)); @@ -101,7 +114,12 @@ public RobotContainer() { new ModuleIO() {}, new ModuleIO() {}, new ModuleIO() {}); - vision = new Vision(drive::addVisionMeasurement, new VisionIO() {}, new VisionIO() {}); + vision = + new Vision( + drive::addVisionMeasurement, + drive::getTimestampedHeading, + new VisionIO() {}, + new VisionIO() {}); break; } diff --git a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java index 6d7a11f..e2cd04c 100644 --- a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java +++ b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java @@ -33,6 +33,7 @@ import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; @@ -49,6 +50,7 @@ import org.team2342.lib.util.SwerveSetpointGenerator; import org.team2342.lib.util.SwerveSetpointGenerator.ModuleLimits; import org.team2342.lib.util.SwerveSetpointGenerator.SwerveSetpoint; +import org.team2342.lib.util.Timestamped; public class Drive extends SubsystemBase { private final GyroIO gyroIO; @@ -357,6 +359,10 @@ public void addVisionMeasurement( visionRobotPoseMeters, timestampSeconds, visionMeasurementStdDevs); } + public Timestamped getTimestampedHeading() { + return new Timestamped(getRotation(), Timer.getFPGATimestamp()); + } + /** Returns an array of module translations. */ public static Translation2d[] getModuleTranslations() { return new Translation2d[] { diff --git a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java index ade06e4..47e7067 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java @@ -19,10 +19,12 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import java.util.LinkedList; import java.util.List; +import java.util.function.Supplier; import org.littletonrobotics.junction.Logger; import org.team2342.frc.Constants.VisionConstants; import org.team2342.frc.subsystems.vision.VisionIO.PoseObservationType; import org.team2342.lib.logging.ExecutionLogger; +import org.team2342.lib.util.Timestamped; public class Vision extends SubsystemBase { private final VisionConsumer consumer; @@ -30,10 +32,17 @@ public class Vision extends SubsystemBase { private final VisionIOInputsAutoLogged[] inputs; private final Alert[] disconnectedAlerts; - public Vision(VisionConsumer consumer, VisionIO... io) { + private final Supplier> timestampedHeading; + + public Vision( + VisionConsumer consumer, + Supplier> timestampedHeading, + VisionIO... io) { this.consumer = consumer; this.io = io; + this.timestampedHeading = timestampedHeading; + // Initialize inputs this.inputs = new VisionIOInputsAutoLogged[io.length]; for (int i = 0; i < inputs.length; i++) { @@ -60,8 +69,12 @@ public Rotation2d getTargetX(int cameraIndex) { @Override public void periodic() { + Timestamped heading = timestampedHeading.get(); + Logger.recordOutput("Vision/TimestampedHeading/Rotation", heading.get()); + Logger.recordOutput("Vision/TimestampedHeading/Timestamp", heading.getTimestamp()); + for (int i = 0; i < io.length; i++) { - io[i].updateInputs(inputs[i]); + io[i].updateInputs(inputs[i], heading); Logger.processInputs("Vision/Camera" + Integer.toString(i), inputs[i]); } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java index 7791bc4..cb47481 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java @@ -10,6 +10,7 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; +import org.team2342.lib.util.Timestamped; public interface VisionIO { @AutoLog @@ -40,7 +41,7 @@ public static enum PoseObservationType { PHOTONVISION_CONSTRAINED } - public default void updateInputs(VisionIOInputs inputs) {} + public default void updateInputs(VisionIOInputs inputs, Timestamped heading) {} public default void toggleHeadingFree() {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOConstrainedSim.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOConstrainedSim.java deleted file mode 100644 index ef77da2..0000000 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOConstrainedSim.java +++ /dev/null @@ -1,62 +0,0 @@ -// Copyright (c) 2025 Team 2342 -// https://github.com/FRCTeamPhoenix -// -// This source code is licensed under the MIT License. -// See the LICENSE file in the root directory of this project. - -package org.team2342.frc.subsystems.vision; - -import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Transform3d; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.numbers.N8; -import java.util.function.Supplier; -import org.photonvision.simulation.PhotonCameraSim; -import org.photonvision.simulation.SimCameraProperties; -import org.photonvision.simulation.VisionSystemSim; -import org.team2342.frc.Constants.VisionConstants; - -public class VisionIOConstrainedSim extends VisionIOPhotonConstrained { - private static VisionSystemSim visionSim; - - private final Supplier poseSupplier; - private final PhotonCameraSim cameraSim; - - /** - * Creates a new VisionIOPhotonVisionSim. - * - * @param name The name of the camera. - * @param poseSupplier Supplier for the robot pose to use in simulation. - */ - public VisionIOConstrainedSim( - String name, - Transform3d robotToCamera, - Supplier rotationSupplier, - Supplier poseSupplier, - Matrix cameraMatrix, - Matrix distCoeffs) { - super(name, robotToCamera, rotationSupplier, cameraMatrix, distCoeffs); - this.poseSupplier = poseSupplier; - - // Initialize vision sim - if (visionSim == null) { - visionSim = new VisionSystemSim("main"); - visionSim.addAprilTags(VisionConstants.TAG_LAYOUT); - } - - // Add sim camera - var cameraProperties = new SimCameraProperties(); - cameraProperties.setCalibration(800, 600, cameraMatrix, distCoeffs); - cameraSim = new PhotonCameraSim(camera, cameraProperties, VisionConstants.TAG_LAYOUT); - visionSim.addCamera(cameraSim, robotToCamera); - } - - @Override - public void updateInputs(VisionIOInputs inputs) { - visionSim.update(poseSupplier.get()); - super.updateInputs(inputs); - } -} diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java index 49eb8ad..d42331f 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java @@ -7,105 +7,117 @@ package org.team2342.frc.subsystems.vision; -import edu.wpi.first.math.geometry.Pose3d; +import edu.wpi.first.apriltag.AprilTagFieldLayout; +import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.math.numbers.N8; import java.util.HashSet; import java.util.LinkedList; import java.util.List; +import java.util.Optional; import java.util.Set; +import org.littletonrobotics.junction.Logger; +import org.photonvision.EstimatedRobotPose; import org.photonvision.PhotonCamera; -import org.team2342.frc.Constants.VisionConstants; +import org.photonvision.PhotonPoseEstimator; +import org.photonvision.PhotonPoseEstimator.PoseStrategy; +import org.photonvision.targeting.PhotonTrackedTarget; +import org.team2342.frc.Constants; +import org.team2342.lib.util.Timestamped; /** IO implementation for real PhotonVision hardware. */ public class VisionIOPhoton implements VisionIO { protected final PhotonCamera camera; protected final Transform3d robotToCamera; + private final PhotonPoseEstimator poseEstimator; + private final CameraParameters parameters; + // TODO: AllianceUtils /** * Creates a new VisionIOPhotonVision. * * @param name The configured name of the camera. * @param robotToCamera The 3D position of the camera relative to the robot. */ - public VisionIOPhoton(String name, Transform3d robotToCamera) { + public VisionIOPhoton( + String name, + CameraParameters parameters, + PoseStrategy poseStrategy, + Transform3d robotToCamera) { camera = new PhotonCamera(name); this.robotToCamera = robotToCamera; + this.parameters = parameters; + poseEstimator = + new PhotonPoseEstimator( + AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField), + poseStrategy, + robotToCamera); + poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.PNP_DISTANCE_TRIG_SOLVE); } @Override - public void updateInputs(VisionIOInputs inputs) { + public void updateInputs(VisionIOInputs inputs, Timestamped heading) { inputs.connected = camera.isConnected(); + poseEstimator.addHeadingData(heading.getTimestamp(), heading.get()); + // Read new camera observations Set tagIds = new HashSet<>(); List poseObservations = new LinkedList<>(); for (var result : camera.getAllUnreadResults()) { - // Update latest target observation - if (result.hasTargets()) { - inputs.latestTargetObservation = - new TargetObservation( - Rotation2d.fromDegrees(result.getBestTarget().getYaw()), - Rotation2d.fromDegrees(result.getBestTarget().getPitch())); - } else { - inputs.latestTargetObservation = new TargetObservation(new Rotation2d(), new Rotation2d()); + if (!result.hasTargets()) { + continue; + } + + Optional optional = + poseEstimator.update( + result, + Optional.ofNullable(parameters.cameraMatrix), + Optional.ofNullable(parameters.distCoeffs), + Constants.VisionConstants.CONSTRAINED_SOLVEPNP_PARAMETERS); + if (optional.isEmpty()) { + continue; } - // Add pose observation - if (result.multitagResult.isPresent()) { // Multitag result - var multitagResult = result.multitagResult.get(); - - // Calculate robot pose - Transform3d fieldToCamera = multitagResult.estimatedPose.best; - Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); - Pose3d robotPose = new Pose3d(fieldToRobot.getTranslation(), fieldToRobot.getRotation()); - - // Calculate average tag distance - double totalTagDistance = 0.0; - for (var target : result.targets) { - totalTagDistance += target.bestCameraToTarget.getTranslation().getNorm(); - } - - // Add tag IDs - tagIds.addAll(multitagResult.fiducialIDsUsed); - - // Add observation - poseObservations.add( - new PoseObservation( - result.getTimestampSeconds(), // Timestamp - robotPose, // 3D pose estimate - multitagResult.estimatedPose.ambiguity, // Ambiguity - multitagResult.fiducialIDsUsed.size(), // Tag count - totalTagDistance / result.targets.size(), // Average tag distance - PoseObservationType.PHOTONVISION)); // Observation type - - } else if (!result.targets.isEmpty()) { // Single tag result - var target = result.targets.get(0); - - // Calculate robot pose - var tagPose = VisionConstants.TAG_LAYOUT.getTagPose(target.fiducialId); - if (tagPose.isPresent()) { - Transform3d fieldToTarget = - new Transform3d(tagPose.get().getTranslation(), tagPose.get().getRotation()); - Transform3d cameraToTarget = target.bestCameraToTarget; - Transform3d fieldToCamera = fieldToTarget.plus(cameraToTarget.inverse()); - Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); - Pose3d robotPose = new Pose3d(fieldToRobot.getTranslation(), fieldToRobot.getRotation()); - - // Add tag ID - tagIds.add((short) target.fiducialId); - - // Add observation - poseObservations.add( - new PoseObservation( - result.getTimestampSeconds(), // Timestamp - robotPose, // 3D pose estimate - target.poseAmbiguity, // Ambiguity - 1, // Tag count - cameraToTarget.getTranslation().getNorm(), // Average tag distance - PoseObservationType.PHOTONVISION)); // Observation type - } + EstimatedRobotPose poseEstimate = optional.get(); + Logger.recordOutput("Vision/Camerui", poseEstimate.strategy); + + double distance = 0; + double ambiguity = 0; + int tagCount = poseEstimate.targetsUsed.size(); + + for (PhotonTrackedTarget target : poseEstimate.targetsUsed) { + distance += target.getBestCameraToTarget().getTranslation().getNorm(); + ambiguity += target.poseAmbiguity; + tagIds.add((short) target.fiducialId); } + + distance /= tagCount; + ambiguity /= tagCount; + + inputs.latestTargetObservation = + new TargetObservation( + Rotation2d.fromDegrees(result.getBestTarget().getYaw()), + Rotation2d.fromDegrees(result.getBestTarget().getPitch())); + + PoseObservationType type = PoseObservationType.PHOTONVISION; + if (poseEstimate.strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) { + type = PoseObservationType.PHOTONVISION_CONSTRAINED; + } + + // Add observation + poseObservations.add( + new PoseObservation( + result.getTimestampSeconds(), // Timestamp + poseEstimate.estimatedPose, // 3D pose estimate + ambiguity, // Ambiguity + tagCount, // Tag count + distance, // Average tag distance + type)); // Observation type } // Save pose observations to inputs object @@ -121,4 +133,6 @@ public void updateInputs(VisionIOInputs inputs) { inputs.tagIds[i++] = id; } } + + public record CameraParameters(Matrix cameraMatrix, Matrix distCoeffs) {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhotonConstrained.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhotonConstrained.java deleted file mode 100644 index 0facc82..0000000 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhotonConstrained.java +++ /dev/null @@ -1,409 +0,0 @@ -// Copyright (c) 2025 Team 2342 -// https://github.com/FRCTeamPhoenix -// -// This source code is licensed under the MIT License. -// See the LICENSE file in the root directory of this project. - -package org.team2342.frc.subsystems.vision; - -import edu.wpi.first.apriltag.AprilTag; -import edu.wpi.first.apriltag.AprilTagFieldLayout; -import edu.wpi.first.cscore.OpenCvLoader; -import edu.wpi.first.math.MatBuilder; -import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Pose3d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Rotation3d; -import edu.wpi.first.math.geometry.Transform3d; -import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.numbers.N8; -import edu.wpi.first.wpilibj.Timer; -import java.util.ArrayList; -import java.util.HashSet; -import java.util.LinkedList; -import java.util.List; -import java.util.Optional; -import java.util.Set; -import java.util.function.Supplier; -import org.ejml.simple.SimpleMatrix; -import org.littletonrobotics.junction.Logger; -import org.opencv.calib3d.Calib3d; -import org.opencv.core.MatOfDouble; -import org.opencv.core.MatOfPoint2f; -import org.opencv.core.Point; -import org.photonvision.PhotonCamera; -import org.photonvision.estimation.OpenCVHelp; -import org.photonvision.estimation.TargetModel; -import org.photonvision.jni.ConstrainedSolvepnpJni; -import org.photonvision.targeting.PhotonPipelineResult; -import org.photonvision.targeting.PhotonTrackedTarget; -import org.photonvision.targeting.TargetCorner; -import org.team2342.frc.Constants.VisionConstants; - -/** IO implementation for real PhotonVision hardware. */ -public class VisionIOPhotonConstrained implements VisionIO { - protected final PhotonCamera camera; - protected final Transform3d robotToCamera; - private final Supplier rotationSupplier; - private final Matrix cameraMatrix; - private final Matrix distCoeffs; - - private final TimeInterpolatableBuffer headingBuffer = - TimeInterpolatableBuffer.createBuffer(1.0); - - private double scalingFactor = 1.0; - private boolean headingFree = true; - - /** - * Creates a new VisionIOPhotonVision. - * - * @param name The configured name of the camera. - * @param robotToCamera The 3D position of the camera relative to the robot. - */ - public VisionIOPhotonConstrained( - String name, - Transform3d robotToCamera, - Supplier rotationSupplier, - Matrix cameraMatrix, - Matrix distCoeffs) { - camera = new PhotonCamera(name); - this.robotToCamera = robotToCamera; - this.rotationSupplier = rotationSupplier; - this.cameraMatrix = cameraMatrix; - this.distCoeffs = distCoeffs; - } - - @Override - public void updateInputs(VisionIOInputs inputs) { - inputs.connected = camera.isConnected(); - - Rotation2d gyro = rotationSupplier.get(); - if (gyro != null) headingBuffer.addSample(Timer.getFPGATimestamp(), gyro); - - // Read new camera observations - Set tagIds = new HashSet<>(); - List poseObservations = new LinkedList<>(); - for (var result : camera.getAllUnreadResults()) { - // Update latest target observation - if (result.hasTargets()) { - inputs.latestTargetObservation = - new TargetObservation( - Rotation2d.fromDegrees(result.getBestTarget().getYaw()), - Rotation2d.fromDegrees(result.getBestTarget().getPitch())); - } else { - inputs.latestTargetObservation = new TargetObservation(new Rotation2d(), new Rotation2d()); - } - - if (!result.targets.isEmpty()) { - PoseObservation observation = constrainedPNP(result, tagIds); - if (observation != null) poseObservations.add(observation); - } - } - - // Save pose observations to inputs object - inputs.poseObservations = new PoseObservation[poseObservations.size()]; - for (int i = 0; i < poseObservations.size(); i++) { - inputs.poseObservations[i] = poseObservations.get(i); - } - - // Save tag IDs to inputs objects - inputs.tagIds = new int[tagIds.size()]; - int i = 0; - for (int id : tagIds) { - inputs.tagIds[i++] = id; - } - } - - private PoseObservation multitag(PhotonPipelineResult result, Set tagIds) { - if (!result.multitagResult.isPresent() - && !result.targets.isEmpty()) { // Check for Multitag result - return basic(result, tagIds); // Fallback - } - var multitagResult = result.multitagResult.get(); - - // Calculate robot pose - Transform3d fieldToCamera = multitagResult.estimatedPose.best; - Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); - Pose3d robotPose = new Pose3d(fieldToRobot.getTranslation(), fieldToRobot.getRotation()); - - // Calculate average tag distance - double totalTagDistance = 0.0; - for (var target : result.targets) { - totalTagDistance += target.bestCameraToTarget.getTranslation().getNorm(); - } - - // Add tag IDs - tagIds.addAll(multitagResult.fiducialIDsUsed); - - // Add observation - return new PoseObservation( - result.getTimestampSeconds(), // Timestamp - robotPose, // 3D pose estimate - multitagResult.estimatedPose.ambiguity, // Ambiguity - multitagResult.fiducialIDsUsed.size(), // Tag count - totalTagDistance / result.targets.size(), // Average tag distance - PoseObservationType.PHOTONVISION); // Observation type - } - - private PoseObservation basic(PhotonPipelineResult result, Set tagIds) { - var target = result.targets.get(0); - - // Calculate robot pose - var tagPose = VisionConstants.TAG_LAYOUT.getTagPose(target.fiducialId); - if (tagPose.isPresent()) { - Transform3d fieldToTarget = - new Transform3d(tagPose.get().getTranslation(), tagPose.get().getRotation()); - Transform3d cameraToTarget = target.bestCameraToTarget; - Transform3d fieldToCamera = fieldToTarget.plus(cameraToTarget.inverse()); - Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); - Pose3d robotPose = new Pose3d(fieldToRobot.getTranslation(), fieldToRobot.getRotation()); - - // Add tag ID - tagIds.add((short) target.fiducialId); - - // Add observation - return new PoseObservation( - result.getTimestampSeconds(), // Timestamp - robotPose, // 3D pose estimate - target.poseAmbiguity, // Ambiguity - 1, // Tag count - cameraToTarget.getTranslation().getNorm(), // Average tag distance - PoseObservationType.PHOTONVISION); // Observation type - } else { - // It's so over, just give up - return null; - } - } - - private PoseObservation constrainedPNP(PhotonPipelineResult result, Set tagIds) { - // Need calibrations - if (distCoeffs == null || cameraMatrix == null) { - return multitag(result, tagIds); - } - - // Need heading - if (headingBuffer.getSample(result.getTimestampSeconds()).isEmpty()) { - return multitag(result, tagIds); - } - - Pose3d fieldToRobotSeed; - var multitagResult = result.getMultiTagResult(); - - double tagDist; - int tagCount; - PoseObservationType type; - - // Attempt to use multi-tag to get a pose estimate seed - if (multitagResult.isPresent()) { - fieldToRobotSeed = - Pose3d.kZero.plus(multitagResult.get().estimatedPose.best.plus(robotToCamera.inverse())); - tagIds.addAll(multitagResult.get().fiducialIDsUsed); - - tagCount = multitagResult.get().fiducialIDsUsed.size(); // Tag count - double totalTagDistance = 0.0; - for (var target : result.targets) { - totalTagDistance += target.bestCameraToTarget.getTranslation().getNorm(); - } - tagDist = totalTagDistance / result.targets.size(); // Average tag distance - } else { - var target = result.targets.get(0); - var tagPose = VisionConstants.TAG_LAYOUT.getTagPose(target.fiducialId); - if (tagPose.isPresent()) { - Transform3d fieldToTarget = - new Transform3d(tagPose.get().getTranslation(), tagPose.get().getRotation()); - Transform3d cameraToTarget = target.bestCameraToTarget; - Transform3d fieldToCamera = fieldToTarget.plus(cameraToTarget.inverse()); - Transform3d fieldToRobot = fieldToCamera.plus(robotToCamera.inverse()); - - tagCount = 1; - tagDist = cameraToTarget.getTranslation().getNorm(); // Average tag distance - fieldToRobotSeed = Pose3d.kZero.plus(fieldToRobot); - } else { - // It's so over, just give up - return null; - } - tagIds.add((short) target.fiducialId); - } - - if (!headingFree) { - fieldToRobotSeed = - new Pose3d( - fieldToRobotSeed.getTranslation(), - new Rotation3d(headingBuffer.getSample(result.getTimestampSeconds()).get())); - type = PoseObservationType.PHOTONVISION_CONSTRAINED; - } else { - type = PoseObservationType.PHOTONVISION; - } - - Logger.recordOutput("Vision/Constrained/Seed", fieldToRobotSeed); - - var constrainedResult = - estimatePoseConstrained( - cameraMatrix, - distCoeffs, - result.getTargets(), - robotToCamera, - fieldToRobotSeed, - VisionConstants.TAG_LAYOUT, - TargetModel.kAprilTag36h11, - headingFree, - headingBuffer.getSample(result.getTimestampSeconds()), - scalingFactor); - - // go to fallback if solvePNP fails for some reason - if (!constrainedResult.isPresent()) { - return multitag(result, tagIds); - } - - return new PoseObservation( - result.getTimestampSeconds(), // Timestamp - constrainedResult.get(), // 3D pose estimate - 0.0, // Ambiguity - tagCount, // Tag count - tagDist, // Average tag distance - type); // Observation type - } - - @Override - public void toggleHeadingFree() { - headingFree = !headingFree; - } - - /** - * "Borrowed" from PhotonVision - * - *

Performs constrained solvePNP using 3d-2d point correspondences of visible AprilTags to - * estimate the field-to-camera transformation. * - * - * @param cameraMatrix The camera intrinsics matrix in standard opencv form - * @param distCoeffs The camera distortion matrix in standard opencv form - * @param visTags The visible tags reported by PV. Non-tag targets are automatically excluded. - * @param robot2camera The {@link Transform3d} from the robot odometry frame to the camera optical - * frame - * @param robotPoseSeed An initial guess at robot pose, refined via optimizaiton. Better guesses - * will converge faster. - * @param tagLayout The known tag layout on the field - * @param tagModel The physical size of the AprilTags - * @param headingFree If heading is completely free, or if our measured gyro is taken into account - * @param gyro If headingFree is false, the best estimate at robot yaw. Excursions from this are - * penalized in our cost function. - * @param gyroErrorScaleFac A relative weight for gyro heading excursions against tag corner - * reprojection error. - * @return The camera pose. Ensure the {@link Pose3d} is present before utilizing it. - */ - public static Optional estimatePoseConstrained( - Matrix cameraMatrix, - Matrix distCoeffs, - List visTags, - Transform3d robot2camera, - Pose3d robotPoseSeed, - AprilTagFieldLayout tagLayout, - TargetModel tagModel, - boolean headingFree, - Optional gyro, - double gyroErrorScaleFac) { - if (tagLayout == null - || visTags == null - || tagLayout.getTags().isEmpty() - || visTags.isEmpty()) { - return Optional.empty(); - } - - var corners = new ArrayList(); - var knownTags = new ArrayList(); - // ensure these are AprilTags in our layout - for (var tgt : visTags) { - int id = tgt.getFiducialId(); - tagLayout - .getTagPose(id) - .ifPresent( - pose -> { - knownTags.add(new AprilTag(id, pose)); - corners.addAll(tgt.getDetectedCorners()); - }); - } - if (knownTags.isEmpty() || corners.isEmpty() || corners.size() % 4 != 0) { - return Optional.empty(); - } - OpenCvLoader.forceStaticLoad(); - - Point[] points = OpenCVHelp.cornersToPoints(corners); - - // Undistort - { - MatOfPoint2f temp = new MatOfPoint2f(); - MatOfDouble cameraMatrixMat = new MatOfDouble(); - MatOfDouble distCoeffsMat = new MatOfDouble(); - OpenCVHelp.matrixToMat(cameraMatrix.getStorage()).assignTo(cameraMatrixMat); - OpenCVHelp.matrixToMat(distCoeffs.getStorage()).assignTo(distCoeffsMat); - - temp.fromArray(points); - Calib3d.undistortImagePoints(temp, temp, cameraMatrixMat, distCoeffsMat); - points = temp.toArray(); - - temp.release(); - cameraMatrixMat.release(); - distCoeffsMat.release(); - } - - // Rotate from wpilib to opencv camera CS - var robot2cameraBase = - MatBuilder.fill(Nat.N4(), Nat.N4(), 0, 0, 1, 0, -1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 0, 1); - var robotToCamera = robot2camera.toMatrix().times(robot2cameraBase); - - // Where we saw corners - var point_observations = new SimpleMatrix(2, points.length); - for (int i = 0; i < points.length; i++) { - point_observations.set(0, i, points[i].x); - point_observations.set(1, i, points[i].y); - } - - // Affine corner locations - var objectTrls = new ArrayList(); - for (var tag : knownTags) objectTrls.addAll(tagModel.getFieldVertices(tag.pose)); - var field2points = new SimpleMatrix(4, points.length); - for (int i = 0; i < objectTrls.size(); i++) { - field2points.set(0, i, objectTrls.get(i).getX()); - field2points.set(1, i, objectTrls.get(i).getY()); - field2points.set(2, i, objectTrls.get(i).getZ()); - field2points.set(3, i, 1); - } - - // fx fy cx cy - double[] cameraCal = - new double[] { - cameraMatrix.get(0, 0), - cameraMatrix.get(1, 1), - cameraMatrix.get(0, 2), - cameraMatrix.get(1, 2), - }; - - var guess2 = robotPoseSeed.toPose2d(); - - var ret = - ConstrainedSolvepnpJni.do_optimization( - headingFree, - knownTags.size(), - cameraCal, - robotToCamera.getData(), - new double[] { - guess2.getX(), guess2.getY(), guess2.getRotation().getRadians(), - }, - field2points.getDDRM().getData(), - point_observations.getDDRM().getData(), - gyro.orElse(Rotation2d.kZero).getRadians(), - gyroErrorScaleFac); - - if (ret == null) { - return Optional.empty(); - } else { - Pose3d poseResult = new Pose3d(new Pose2d(ret[0], ret[1], new Rotation2d(ret[2]))); - return Optional.of(poseResult); - } - } -} diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java index 2e169a7..c6dd337 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java @@ -8,12 +8,15 @@ package org.team2342.frc.subsystems.vision; import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform3d; import java.util.function.Supplier; +import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.photonvision.simulation.PhotonCameraSim; import org.photonvision.simulation.SimCameraProperties; import org.photonvision.simulation.VisionSystemSim; import org.team2342.frc.Constants.VisionConstants; +import org.team2342.lib.util.Timestamped; /** IO implementation for physics sim using PhotonVision simulator. */ public class VisionIOSim extends VisionIOPhoton { @@ -28,8 +31,13 @@ public class VisionIOSim extends VisionIOPhoton { * @param name The name of the camera. * @param poseSupplier Supplier for the robot pose to use in simulation. */ - public VisionIOSim(String name, Transform3d robotToCamera, Supplier poseSupplier) { - super(name, robotToCamera); + public VisionIOSim( + String name, + CameraParameters parameters, + PoseStrategy poseStrategy, + Transform3d robotToCamera, + Supplier poseSupplier) { + super(name, parameters, poseStrategy, robotToCamera); this.poseSupplier = poseSupplier; // Initialize vision sim @@ -45,8 +53,8 @@ public VisionIOSim(String name, Transform3d robotToCamera, Supplier pose } @Override - public void updateInputs(VisionIOInputs inputs) { + public void updateInputs(VisionIOInputs inputs, Timestamped heading) { visionSim.update(poseSupplier.get()); - super.updateInputs(inputs); + super.updateInputs(inputs, heading); } } diff --git a/src/main/java/org/team2342/lib/util/Timestamped.java b/src/main/java/org/team2342/lib/util/Timestamped.java new file mode 100644 index 0000000..f5c72d8 --- /dev/null +++ b/src/main/java/org/team2342/lib/util/Timestamped.java @@ -0,0 +1,28 @@ +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix +// +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. + +package org.team2342.lib.util; + +import java.util.function.Supplier; + +public class Timestamped implements Supplier { + private T object; + private double timestamp; + + public Timestamped(T object, double timestamp) { + this.object = object; + this.timestamp = timestamp; + } + + @Override + public T get() { + return object; + } + + public double getTimestamp() { + return timestamp; + } +} From 585e9f380bee34866cb37d1643f94f2f1fca88c7 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Sun, 7 Dec 2025 22:04:02 -0500 Subject: [PATCH 2/7] adding gyro cleanup as well --- build.gradle | 3 -- src/main/java/org/team2342/frc/Constants.java | 5 ++- .../java/org/team2342/frc/RobotContainer.java | 12 +++++- .../team2342/frc/subsystems/drive/Drive.java | 10 ++++- .../frc/subsystems/vision/Vision.java | 14 +++---- .../frc/subsystems/vision/VisionIO.java | 2 - .../frc/subsystems/vision/VisionIOPhoton.java | 42 +++++++++++-------- .../frc/subsystems/vision/VisionIOSim.java | 30 ++++++++----- 8 files changed, 72 insertions(+), 46 deletions(-) diff --git a/build.gradle b/build.gradle index fdcd82f..14ab1da 100644 --- a/build.gradle +++ b/build.gradle @@ -216,11 +216,8 @@ spotless { include "**/*.java" exclude "**/build/**", "**/build-*/**" exclude "src/main/java/org/team2342/frc/commands/DriveCommands.java" - exclude "src/main/java/org/team2342/frc/commands/DriveCommands.java" exclude "src/main/java/org/team2342/frc/subsystems/vision/Vision.java" exclude "src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java" - exclude "src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java" - exclude "src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java" } licenseHeader("// Copyright (c) $currentYear Team 2342\n// https://github.com/FRCTeamPhoenix\n//\n// This source code is licensed under the MIT License.\n// See the LICENSE file in the root directory of this project.\n\n", "package ") // Your actual license header diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 824e2c9..e9c0eb9 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -20,7 +20,7 @@ import edu.wpi.first.math.util.Units; import java.util.Optional; import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; -import org.team2342.frc.subsystems.vision.VisionIOPhoton.CameraParameters; +import org.team2342.frc.subsystems.vision.Vision.CameraParameters; public final class Constants { public static final Mode CURRENT_MODE = Mode.SIM; @@ -87,9 +87,10 @@ public static final class VisionConstants { 0.003667258530403619, -0.0014957440403602612); public static final CameraParameters PARAMETERS = - new CameraParameters(cameraMatrix, distCoeffs); + new CameraParameters(800, 600, cameraMatrix, distCoeffs); public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); + // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; public static final double MAX_Z_ERROR = 0.75; diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index bb4b25f..937985b 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -69,11 +69,13 @@ public RobotContainer() { VisionConstants.RIGHT_CAMERA_NAME, VisionConstants.PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_RIGHT_TRANSFORM), new VisionIOPhoton( VisionConstants.LEFT_CAMERA_NAME, VisionConstants.PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_LEFT_TRANSFORM)); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); @@ -94,13 +96,15 @@ public RobotContainer() { new VisionIOSim( VisionConstants.RIGHT_CAMERA_NAME, VisionConstants.PARAMETERS, - PoseStrategy.PNP_DISTANCE_TRIG_SOLVE, + PoseStrategy.CONSTRAINED_SOLVEPNP, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_RIGHT_TRANSFORM, drive::getRawOdometryPose), new VisionIOSim( VisionConstants.LEFT_CAMERA_NAME, VisionConstants.PARAMETERS, - PoseStrategy.PNP_DISTANCE_TRIG_SOLVE, + PoseStrategy.CONSTRAINED_SOLVEPNP, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_LEFT_TRANSFORM, drive::getRawOdometryPose)); @@ -129,6 +133,10 @@ public RobotContainer() { autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); autoChooser.get(); + SmartDashboard.putData( + "Calculate Vision Heading Offset", + Commands.runOnce(() -> drive.calculateVisionHeadingOffset())); + if (Constants.TUNING) setupDevelopmentRoutines(); configureBindings(); diff --git a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java index e2cd04c..23d405b 100644 --- a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java +++ b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java @@ -70,6 +70,9 @@ public class Drive extends SubsystemBase { private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations()); private Rotation2d rawGyroRotation = new Rotation2d(); + @AutoLogOutput(key = "Vision/Heading/Offset") + private Rotation2d visionHeadingOffset = new Rotation2d(); + private SwerveModulePosition[] lastModulePositions = // For delta tracking new SwerveModulePosition[] { new SwerveModulePosition(), @@ -360,7 +363,12 @@ public void addVisionMeasurement( } public Timestamped getTimestampedHeading() { - return new Timestamped(getRotation(), Timer.getFPGATimestamp()); + return new Timestamped( + rawGyroRotation.minus(visionHeadingOffset), Timer.getFPGATimestamp()); + } + + public void calculateVisionHeadingOffset() { + visionHeadingOffset = rawGyroRotation.minus(getRotation()); } /** Returns an array of module translations. */ diff --git a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java index 47e7067..4e3a367 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java @@ -14,6 +14,7 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.math.numbers.N8; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -70,8 +71,8 @@ public Rotation2d getTargetX(int cameraIndex) { @Override public void periodic() { Timestamped heading = timestampedHeading.get(); - Logger.recordOutput("Vision/TimestampedHeading/Rotation", heading.get()); - Logger.recordOutput("Vision/TimestampedHeading/Timestamp", heading.getTimestamp()); + Logger.recordOutput("Vision/Heading/Rotation", heading.get()); + Logger.recordOutput("Vision/Heading/Timestamp", heading.getTimestamp()); for (int i = 0; i < io.length; i++) { io[i].updateInputs(inputs[i], heading); @@ -187,12 +188,6 @@ public void periodic() { ExecutionLogger.log("Vision"); } - public void toggleHeadingsFree() { - for (VisionIO vis : io) { - vis.toggleHeadingFree(); - } - } - @FunctionalInterface public static interface VisionConsumer { public void accept( @@ -200,4 +195,7 @@ public void accept( double timestampSeconds, Matrix visionMeasurementStdDevs); } + + public record CameraParameters( + int resWidth, int resHeight, Matrix cameraMatrix, Matrix distCoeffs) {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java index cb47481..8a28308 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java @@ -42,6 +42,4 @@ public static enum PoseObservationType { } public default void updateInputs(VisionIOInputs inputs, Timestamped heading) {} - - public default void toggleHeadingFree() {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java index d42331f..f5ce1f7 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java @@ -1,32 +1,28 @@ -// Copyright (c) 2021-2025 Littleton Robotics -// http://github.com/Mechanical-Advantage +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix // -// Use of this source code is governed by a BSD -// license that can be found in the AdvantageKit-License file -// at the root directory of this project. +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. package org.team2342.frc.subsystems.vision; import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; -import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform3d; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.numbers.N8; +import edu.wpi.first.wpilibj.DriverStation; import java.util.HashSet; import java.util.LinkedList; import java.util.List; import java.util.Optional; import java.util.Set; -import org.littletonrobotics.junction.Logger; import org.photonvision.EstimatedRobotPose; import org.photonvision.PhotonCamera; import org.photonvision.PhotonPoseEstimator; import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.photonvision.targeting.PhotonTrackedTarget; import org.team2342.frc.Constants; +import org.team2342.frc.subsystems.vision.Vision.CameraParameters; import org.team2342.lib.util.Timestamped; /** IO implementation for real PhotonVision hardware. */ @@ -34,8 +30,13 @@ public class VisionIOPhoton implements VisionIO { protected final PhotonCamera camera; protected final Transform3d robotToCamera; private final PhotonPoseEstimator poseEstimator; + + private final PoseStrategy primaryStrategy; + private final CameraParameters parameters; + private boolean hasEnabled = false; + // TODO: AllianceUtils /** * Creates a new VisionIOPhotonVision. @@ -46,7 +47,8 @@ public class VisionIOPhoton implements VisionIO { public VisionIOPhoton( String name, CameraParameters parameters, - PoseStrategy poseStrategy, + PoseStrategy primaryStrategy, + PoseStrategy disabledStrategy, Transform3d robotToCamera) { camera = new PhotonCamera(name); this.robotToCamera = robotToCamera; @@ -54,13 +56,20 @@ public VisionIOPhoton( poseEstimator = new PhotonPoseEstimator( AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField), - poseStrategy, + disabledStrategy, robotToCamera); - poseEstimator.setMultiTagFallbackStrategy(PoseStrategy.PNP_DISTANCE_TRIG_SOLVE); + this.primaryStrategy = primaryStrategy; } @Override public void updateInputs(VisionIOInputs inputs, Timestamped heading) { + if (!hasEnabled) { + if (DriverStation.isEnabled()) { + poseEstimator.setPrimaryStrategy(primaryStrategy); + hasEnabled = true; + } + } + inputs.connected = camera.isConnected(); poseEstimator.addHeadingData(heading.getTimestamp(), heading.get()); @@ -76,15 +85,14 @@ public void updateInputs(VisionIOInputs inputs, Timestamped heading) Optional optional = poseEstimator.update( result, - Optional.ofNullable(parameters.cameraMatrix), - Optional.ofNullable(parameters.distCoeffs), + Optional.ofNullable(parameters.cameraMatrix()), + Optional.ofNullable(parameters.distCoeffs()), Constants.VisionConstants.CONSTRAINED_SOLVEPNP_PARAMETERS); if (optional.isEmpty()) { continue; } EstimatedRobotPose poseEstimate = optional.get(); - Logger.recordOutput("Vision/Camerui", poseEstimate.strategy); double distance = 0; double ambiguity = 0; @@ -133,6 +141,4 @@ public void updateInputs(VisionIOInputs inputs, Timestamped heading) inputs.tagIds[i++] = id; } } - - public record CameraParameters(Matrix cameraMatrix, Matrix distCoeffs) {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java index c6dd337..6a651da 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java @@ -1,9 +1,8 @@ -// Copyright (c) 2021-2025 Littleton Robotics -// http://github.com/Mechanical-Advantage +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix // -// Use of this source code is governed by a BSD -// license that can be found in the AdvantageKit-License file -// at the root directory of this project. +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. package org.team2342.frc.subsystems.vision; @@ -16,6 +15,7 @@ import org.photonvision.simulation.SimCameraProperties; import org.photonvision.simulation.VisionSystemSim; import org.team2342.frc.Constants.VisionConstants; +import org.team2342.frc.subsystems.vision.Vision.CameraParameters; import org.team2342.lib.util.Timestamped; /** IO implementation for physics sim using PhotonVision simulator. */ @@ -34,21 +34,31 @@ public class VisionIOSim extends VisionIOPhoton { public VisionIOSim( String name, CameraParameters parameters, - PoseStrategy poseStrategy, + PoseStrategy primaryStrategy, + PoseStrategy disabledStrategy, Transform3d robotToCamera, Supplier poseSupplier) { - super(name, parameters, poseStrategy, robotToCamera); + super(name, parameters, primaryStrategy, disabledStrategy, robotToCamera); this.poseSupplier = poseSupplier; - // Initialize vision sim if (visionSim == null) { visionSim = new VisionSystemSim("main"); visionSim.addAprilTags(VisionConstants.TAG_LAYOUT); } // Add sim camera - var cameraProperties = new SimCameraProperties(); - cameraSim = new PhotonCameraSim(camera, cameraProperties, VisionConstants.TAG_LAYOUT); + SimCameraProperties properties = new SimCameraProperties(); + properties.setCalibration( + parameters.resWidth(), + parameters.resHeight(), + parameters.cameraMatrix(), + parameters.distCoeffs()); + properties.setCalibError(0.02, 0.05); + properties.setFPS(60); + properties.setAvgLatencyMs(35); + properties.setLatencyStdDevMs(7); + + cameraSim = new PhotonCameraSim(camera, properties, VisionConstants.TAG_LAYOUT); visionSim.addCamera(cameraSim, robotToCamera); } From ea039ed2d53a320776905a7dfb8a772bc3646674 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Mon, 8 Dec 2025 08:45:04 -0500 Subject: [PATCH 3/7] timestamped lombok --- src/main/java/org/team2342/frc/Constants.java | 2 +- src/main/java/org/team2342/lib/util/Timestamped.java | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index e9c0eb9..13636f1 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -90,7 +90,7 @@ public static final class VisionConstants { new CameraParameters(800, 600, cameraMatrix, distCoeffs); public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); - + // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; public static final double MAX_Z_ERROR = 0.75; diff --git a/src/main/java/org/team2342/lib/util/Timestamped.java b/src/main/java/org/team2342/lib/util/Timestamped.java index f5c72d8..d882ff3 100644 --- a/src/main/java/org/team2342/lib/util/Timestamped.java +++ b/src/main/java/org/team2342/lib/util/Timestamped.java @@ -7,10 +7,12 @@ package org.team2342.lib.util; import java.util.function.Supplier; +import lombok.Getter; public class Timestamped implements Supplier { private T object; - private double timestamp; + + @Getter private double timestamp; public Timestamped(T object, double timestamp) { this.object = object; @@ -21,8 +23,4 @@ public Timestamped(T object, double timestamp) { public T get() { return object; } - - public double getTimestamp() { - return timestamp; - } } From e64e1a27c688c4ae84e3be890cea6bfeed859437 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Mon, 8 Dec 2025 14:34:29 -0500 Subject: [PATCH 4/7] adding cameraparameters class --- build.gradle | 2 +- .../deploy/calibrations/left_arducam_800.json | 1 + .../calibrations/right_arducam_800.json | 1 + src/main/java/org/team2342/frc/Constants.java | 40 +---- .../java/org/team2342/frc/RobotContainer.java | 12 +- .../frc/subsystems/vision/Vision.java | 4 - .../frc/subsystems/vision/VisionIOPhoton.java | 12 +- .../frc/subsystems/vision/VisionIOSim.java | 17 +- .../team2342/lib/util/CameraParameters.java | 161 ++++++++++++++++++ 9 files changed, 187 insertions(+), 63 deletions(-) create mode 100644 src/main/deploy/calibrations/left_arducam_800.json create mode 100644 src/main/deploy/calibrations/right_arducam_800.json create mode 100644 src/main/java/org/team2342/lib/util/CameraParameters.java diff --git a/build.gradle b/build.gradle index 14ab1da..fe09ed7 100644 --- a/build.gradle +++ b/build.gradle @@ -220,7 +220,7 @@ spotless { exclude "src/main/java/org/team2342/frc/subsystems/vision/VisionIO.java" } - licenseHeader("// Copyright (c) $currentYear Team 2342\n// https://github.com/FRCTeamPhoenix\n//\n// This source code is licensed under the MIT License.\n// See the LICENSE file in the root directory of this project.\n\n", "package ") // Your actual license header + licenseHeader("// Copyright (c) $currentYear Team 2342\n// https://github.com/FRCTeamPhoenix\n//\n// This source code is licensed under the MIT License.\n// See the LICENSE file in the root directory of this project.\n\n", "package ") } groovyGradle { target fileTree(".") { diff --git a/src/main/deploy/calibrations/left_arducam_800.json b/src/main/deploy/calibrations/left_arducam_800.json new file mode 100644 index 0000000..dce0ae1 --- /dev/null +++ b/src/main/deploy/calibrations/left_arducam_800.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[680.3518437477294,0.0,393.34429560711095,0.0,681.5148816063638,304.5111454902841,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04913279370181987,-0.08080811604393605,0.0012713783068216294,-9.086414571538155E-4,0.03813939624862079,-0.002083234186226857,0.003667258530403619,-0.0014957440403602612]},"calobjectWarp":[-2.4222652881449006E-4,-7.403314167453361E-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.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.63787841796875,"y":201.96435546875},{"x":420.0296936035156,"y":203.2669219970703},{"x":444.2115783691406,"y":204.21347045898438},{"x":468.8716735839844,"y":205.87741088867188},{"x":492.6279296875,"y":206.98814392089844},{"x":516.905517578125,"y":208.358642578125},{"x":540.6669921875,"y":209.6805419921875},{"x":394.31170654296875,"y":226.8882293701172},{"x":418.8793640136719,"y":227.9027099609375},{"x":442.83978271484375,"y":228.966064453125},{"x":467.054931640625,"y":230.47303771972656},{"x":490.9638366699219,"y":231.596435546875},{"x":514.9796142578125,"y":232.9580078125},{"x":538.2432250976562,"y":234.12216186523438},{"x":392.8952941894531,"y":251.2106170654297},{"x":417.048095703125,"y":252.2500457763672},{"x":441.32562255859375,"y":253.8323516845703},{"x":465.17327880859375,"y":254.6101531982422},{"x":489.1075439453125,"y":255.8332977294922},{"x":512.9839477539062,"y":257.06500244140625},{"x":536.1762084960938,"y":258.12213134765625},{"x":391.6473693847656,"y":275.9429016113281},{"x":415.8117370605469,"y":276.5908508300781},{"x":439.90936279296875,"y":277.9654541015625},{"x":463.9397277832031,"y":279.0257568359375},{"x":487.305419921875,"y":279.9642639160156},{"x":510.98260498046875,"y":281.11273193359375},{"x":534.46923828125,"y":282.29754638671875},{"x":390.2811279296875,"y":299.2279052734375},{"x":414.2469177246094,"y":300.66754150390625},{"x":438.0099182128906,"y":301.4851989746094},{"x":462.0777587890625,"y":302.62823486328125},{"x":485.6961364746094,"y":303.857666015625},{"x":509.1346740722656,"y":304.3945007324219},{"x":532.2939453125,"y":305.8572082519531},{"x":388.7101745605469,"y":322.96112060546875},{"x":412.8590087890625,"y":324.3318786621094},{"x":436.7467041015625,"y":325.2496643066406},{"x":460.26776123046875,"y":326.05523681640625},{"x":483.86956787109375,"y":327.3586730957031},{"x":507.3291320800781,"y":328.107666015625},{"x":530.8265991210938,"y":329.02960205078125},{"x":387.98370361328125,"y":346.7546691894531},{"x":411.718017578125,"y":347.8789367675781},{"x":434.97021484375,"y":348.78057861328125},{"x":458.7391357421875,"y":349.7117614746094},{"x":482.2115173339844,"y":350.461669921875},{"x":505.65484619140625,"y":351.5047912597656},{"x":528.6858520507812,"y":352.2821350097656}],"reprojectionErrors":[{"x":-0.078582763671875,"y":-0.1130523681640625},{"x":0.03668212890625,"y":-0.0861358642578125},{"x":0.233642578125,"y":0.289947509765625},{"x":-0.178924560546875,"y":-0.0583953857421875},{"x":0.17803955078125,"y":0.1392822265625},{"x":-0.12353515625,"y":0.069854736328125},{"x":-0.04901123046875,"y":0.0415191650390625},{"x":-0.070159912109375,"y":-0.2250518798828125},{"x":-0.255615234375,"y":0.02093505859375},{"x":0.039306640625,"y":0.2102203369140625},{"x":-0.0504150390625,"y":-0.052093505859375},{"x":0.03326416015625,"y":0.06103515625},{"x":-0.12567138671875,"y":-0.0722808837890625},{"x":0.3289794921875,"y":-0.016571044921875},{"x":0.041473388671875,"y":0.0047760009765625},{"x":0.146881103515625,"y":0.1581573486328125},{"x":0.002044677734375,"y":-0.240142822265625},{"x":0.1585693359375,"y":0.157135009765625},{"x":0.097015380859375,"y":0.1000213623046875},{"x":-0.04095458984375,"y":0.025177001953125},{"x":0.3680419921875,"y":0.115631103515625},{"x":-0.00250244140625,"y":-0.43212890625},{"x":-0.031829833984375,"y":0.04638671875},{"x":-0.11859130859375,"y":-0.211517333984375},{"x":-0.265228271484375,"y":-0.164947509765625},{"x":0.122772216796875,"y":-0.00653076171875},{"x":0.06634521484375,"y":-0.068145751953125},{"x":0.0648193359375,"y":-0.17626953125},{"x":0.08453369140625,"y":0.324188232421875},{"x":0.1314697265625,"y":-0.054046630859375},{"x":0.25836181640625,"y":0.179046630859375},{"x":-0.045379638671875,"y":0.07598876953125},{"x":-0.028350830078125,"y":-0.124298095703125},{"x":0.03704833984375,"y":0.357086181640625},{"x":0.2474365234375,"y":-0.098419189453125},{"x":0.388885498046875,"y":0.381011962890625},{"x":0.131317138671875,"y":0.00787353515625},{"x":0.013336181640625,"y":0.076141357421875},{"x":0.137542724609375,"y":0.244964599609375},{"x":0.053680419921875,"y":-0.095794677734375},{"x":-0.018035888671875,"y":0.106109619140625},{"x":-0.260498046875,"y":0.12322998046875},{"x":-0.1387939453125,"y":0.12890625},{"x":-0.102508544921875,"y":-0.06024169921875},{"x":0.295684814453125,"y":-0.03924560546875},{"x":0.05401611328125,"y":-0.060333251953125},{"x":-0.017120361328125,"y":0.0872802734375},{"x":-0.18792724609375,"y":-0.070953369140625},{"x":-0.077880859375,"y":0.02392578125}],"optimisedCameraToObject":{"translation":{"x":-0.021683619027386893,"y":-0.13177694641447624,"z":0.6954322613892415},"rotation":{"quaternion":{"W":0.9963415936377188,"X":0.07429111312104363,"Y":-0.03464091969580141,"Z":0.024171594513314607}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":545.0081176757812,"y":214.97610473632812},{"x":567.103515625,"y":216.0049591064453},{"x":589.0089111328125,"y":216.98973083496094},{"x":610.510009765625,"y":218.22630310058594},{"x":631.96826171875,"y":219.06700134277344},{"x":653.1405029296875,"y":220.07257080078125},{"x":674.0646362304688,"y":221.20545959472656},{"x":543.9988403320312,"y":238.06126403808594},{"x":565.9149780273438,"y":239.13587951660156},{"x":587.8931884765625,"y":239.9783935546875},{"x":609.7720336914062,"y":240.8497772216797},{"x":631.0768432617188,"y":241.94493103027344},{"x":652.2105712890625,"y":242.7381134033203},{"x":672.8532104492188,"y":243.63467407226562},{"x":542.92822265625,"y":261.2977294921875},{"x":565.1015625,"y":262.0004577636719},{"x":586.6165161132812,"y":263.18701171875},{"x":608.23974609375,"y":263.8254699707031},{"x":629.5731201171875,"y":264.30181884765625},{"x":651.0245971679688,"y":265.15216064453125},{"x":671.7772216796875,"y":266.10601806640625},{"x":542.0488891601562,"y":284.6033935546875},{"x":564.0,"y":285.24639892578125},{"x":585.701904296875,"y":285.86431884765625},{"x":607.5843505859375,"y":286.44683837890625},{"x":629.022705078125,"y":287.1971740722656},{"x":650.05859375,"y":287.9716796875},{"x":671.0332641601562,"y":288.6597595214844},{"x":540.9203491210938,"y":307.23004150390625},{"x":562.9186401367188,"y":307.91412353515625},{"x":584.7335205078125,"y":308.21905517578125},{"x":606.27001953125,"y":309.10003662109375},{"x":627.8847045898438,"y":309.7110900878906},{"x":648.9175415039062,"y":310.220703125},{"x":669.8855590820312,"y":310.5852966308594},{"x":540.0347290039062,"y":330.3905029296875},{"x":561.883056640625,"y":331.00128173828125},{"x":583.7084350585938,"y":331.28564453125},{"x":605.1730346679688,"y":331.8525695800781},{"x":626.6658935546875,"y":332.0289001464844},{"x":647.9277954101562,"y":333.0074462890625},{"x":668.8612060546875,"y":333.46392822265625},{"x":538.8889770507812,"y":353.0419006347656},{"x":561.0779418945312,"y":353.19757080078125},{"x":582.8048706054688,"y":353.9272155761719},{"x":604.15380859375,"y":354.31658935546875},{"x":625.7700805664062,"y":354.94219970703125},{"x":647.063720703125,"y":355.2154541015625},{"x":667.9808959960938,"y":355.6434631347656}],"reprojectionErrors":[{"x":-0.07733154296875,"y":-0.0243377685546875},{"x":-0.07965087890625,"y":-0.0109710693359375},{"x":-0.1033935546875,"y":0.040252685546875},{"x":0.06512451171875,"y":-0.166656494140625},{"x":0.06402587890625,"y":0.0159149169921875},{"x":0.1361083984375,"y":0.02716064453125},{"x":0.24310302734375,"y":-0.0954437255859375},{"x":-0.0216064453125,"y":0.069305419921875},{"x":0.1318359375,"y":-0.06781005859375},{"x":0.0123291015625,"y":0.0206756591796875},{"x":-0.21929931640625,"y":0.0737457275390625},{"x":-0.08880615234375,"y":-0.1035614013671875},{"x":4.2724609375E-4,"y":0.0144500732421875},{"x":0.3680419921875,"y":0.022369384765625},{"x":0.093994140625,"y":-0.046478271484375},{"x":-0.03350830078125,"y":0.084075927734375},{"x":0.28704833984375,"y":-0.27593994140625},{"x":0.288330078125,"y":-0.09466552734375},{"x":0.36810302734375,"y":0.241912841796875},{"x":0.117919921875,"y":0.197662353515625},{"x":0.35443115234375,"y":0.042999267578125},{"x":0.01690673828125,"y":-0.290435791015625},{"x":0.08758544921875,"y":-0.203857421875},{"x":0.19769287109375,"y":-0.099212646484375},{"x":-0.08319091796875,"y":0.0338134765625},{"x":-0.130859375,"y":-0.00799560546875},{"x":0.01263427734375,"y":-0.081024169921875},{"x":0.0057373046875,"y":-0.07470703125},{"x":0.1876220703125,"y":0.08477783203125},{"x":0.1868896484375,"y":0.027069091796875},{"x":0.16021728515625,"y":0.341278076171875},{"x":0.20208740234375,"y":0.072174072265625},{"x":-0.04461669921875,"y":0.06573486328125},{"x":0.07977294921875,"y":0.153533935546875},{"x":0.057861328125,"y":0.37908935546875},{"x":0.1141357421875,"y":-0.134552001953125},{"x":0.23876953125,"y":-0.22161865234375},{"x":0.1776123046875,"y":0.010223388671875},{"x":0.267822265625,"y":-0.0479736328125},{"x":0.1199951171875,"y":0.2769775390625},{"x":-0.007080078125,"y":-0.207733154296875},{"x":-0.01629638671875,"y":-0.177825927734375},{"x":0.299560546875,"y":0.09356689453125},{"x":0.0587158203125,"y":0.3594970703125},{"x":0.0716552734375,"y":0.043701171875},{"x":0.2537841796875,"y":0.060455322265625},{"x":-0.04071044921875,"y":-0.166717529296875},{"x":-0.22222900390625,"y":-0.0491943359375},{"x":-0.23736572265625,"y":-0.093994140625}],"optimisedCameraToObject":{"translation":{"x":0.14245953064245973,"y":-0.12445481468657799,"z":0.7443504518235929},"rotation":{"quaternion":{"W":0.9973960137872739,"X":0.020145460484844304,"Y":-0.06754135983809383,"Z":0.015281256961737955}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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}],"locationInImageSpace":[{"x":637.35009765625,"y":223.87112426757812},{"x":658.77880859375,"y":224.62010192871094},{"x":679.959228515625,"y":225.6707763671875},{"x":700.463623046875,"y":226.93467712402344},{"x":721.117919921875,"y":227.92007446289062},{"x":741.12353515625,"y":229.05091857910156},{"x":760.9057006835938,"y":230.06553649902344},{"x":636.3917846679688,"y":246.91290283203125},{"x":657.5963745117188,"y":247.46505737304688},{"x":678.8309326171875,"y":248.7857208251953},{"x":699.7490234375,"y":248.8679656982422},{"x":720.1301879882812,"y":250.70465087890625},{"x":740.2091674804688,"y":251.4678192138672},{"x":759.989501953125,"y":252.2472381591797},{"x":635.3759155273438,"y":270.10894775390625},{"x":656.8347778320312,"y":270.8260192871094},{"x":677.8392333984375,"y":271.9836730957031},{"x":698.5076293945312,"y":272.5318908691406},{"x":718.9074096679688,"y":273.3147888183594},{"x":739.0045776367188,"y":274.07147216796875},{"x":759.0926513671875,"y":274.8702697753906},{"x":633.1982421875,"y":291.47125244140625},{"x":655.77587890625,"y":294.0335388183594},{"x":676.6984252929688,"y":294.57183837890625},{"x":697.7639770507812,"y":295.3775634765625},{"x":718.1151733398438,"y":295.98651123046875},{"x":738.515869140625,"y":296.8659973144531},{"x":757.906494140625,"y":297.4889221191406},{"x":633.0443725585938,"y":316.19464111328125},{"x":654.3695678710938,"y":316.8802795410156},{"x":675.6729125976562,"y":317.1841735839844},{"x":696.2865600585938,"y":317.9710388183594},{"x":716.9566650390625,"y":318.2099304199219},{"x":737.3704833984375,"y":318.9745178222656},{"x":757.2713623046875,"y":319.537109375},{"x":632.0281982421875,"y":339.64007568359375},{"x":653.4033813476562,"y":340.02239990234375},{"x":674.5950927734375,"y":340.1749572753906},{"x":695.5606079101562,"y":340.5608825683594},{"x":715.9942626953125,"y":341.0128173828125},{"x":736.1583251953125,"y":341.24932861328125},{"x":756.4220581054688,"y":341.9186706542969},{"x":631.2296142578125,"y":362.1596984863281},{"x":652.7010498046875,"y":362.4485168457031},{"x":673.944580078125,"y":362.9244079589844},{"x":694.4776611328125,"y":363.163818359375},{"x":715.1163940429688,"y":363.8038635253906}],"reprojectionErrors":[{"x":9.1552734375E-4,"y":-0.4399566650390625},{"x":-0.0999755859375,"y":-0.0617523193359375},{"x":-0.21307373046875,"y":0.0051116943359375},{"x":0.0904541015625,"y":-0.1508941650390625},{"x":-0.01397705078125,"y":-0.038055419921875},{"x":0.27337646484375,"y":-0.0803375244140625},{"x":0.5286865234375,"y":-0.0160369873046875},{"x":-0.00299072265625,"y":-0.24554443359375},{"x":0.1090087890625,"y":0.1974029541015625},{"x":-0.069091796875,"y":-0.137481689453125},{"x":-0.189697265625,"y":0.7567138671875},{"x":-0.0311279296875,"y":-0.11285400390625},{"x":0.17315673828125,"y":0.081787109375},{"x":0.4208984375,"y":0.250885009765625},{"x":0.04638671875,"y":-0.241607666015625},{"x":-0.107421875,"y":-0.095245361328125},{"x":-0.0665283203125,"y":-0.39849853515625},{"x":0.0518798828125,"y":-0.101348876953125},{"x":0.18145751953125,"y":-0.0478515625},{"x":0.3575439453125,"y":0.02288818359375},{"x":0.28790283203125,"y":0.042572021484375},{"x":1.25341796875,"y":1.558807373046875},{"x":-0.03094482421875,"y":-0.27130126953125},{"x":0.0804443359375,"y":-0.086181640625},{"x":-0.2093505859375,"y":-0.17718505859375},{"x":-0.04180908203125,"y":-0.080047607421875},{"x":-0.17950439453125,"y":-0.262115478515625},{"x":0.43841552734375,"y":-0.1961669921875},{"x":0.43255615234375,"y":-0.04010009765625},{"x":0.3885498046875,"y":-0.124420166015625},{"x":0.10748291015625,"y":0.164581298828125},{"x":0.25823974609375,"y":-0.037811279296875},{"x":0.095947265625,"y":0.2994384765625},{"x":-0.06536865234375,"y":0.10272216796875},{"x":0.0321044921875,"y":0.099761962890625},{"x":0.469970703125,"y":-0.400299072265625},{"x":0.36358642578125,"y":-0.311737060546875},{"x":0.18212890625,"y":-0.00152587890625},{"x":-0.030517578125,"y":0.06719970703125},{"x":0.032470703125,"y":0.061920166015625},{"x":0.11004638671875,"y":0.26409912109375},{"x":-0.16571044921875,"y":0.025604248046875},{"x":0.28582763671875,"y":0.12506103515625},{"x":0.07049560546875,"y":0.177154541015625},{"x":-0.175048828125,"y":0.0343017578125},{"x":0.0328369140625,"y":0.12017822265625},{"x":-0.12066650390625,"y":-0.2022705078125}],"optimisedCameraToObject":{"translation":{"x":0.24329282913901001,"y":-0.11484819209175529,"z":0.7410535630740036},"rotation":{"quaternion":{"W":0.9961612850501481,"X":0.013382385078883376,"Y":-0.08508084968790397,"Z":0.015647841807173553}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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.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":638.1043090820312,"y":344.4933776855469},{"x":659.035400390625,"y":345.93658447265625},{"x":679.9313354492188,"y":346.6091003417969},{"x":700.3306274414062,"y":347.8829040527344},{"x":720.4559936523438,"y":348.86962890625},{"x":637.201904296875,"y":367.73736572265625},{"x":658.0675048828125,"y":368.0691223144531},{"x":679.0016479492188,"y":369.27239990234375},{"x":699.8268432617188,"y":370.36151123046875},{"x":720.205078125,"y":371.1315002441406},{"x":636.127197265625,"y":390.8311767578125},{"x":657.3150634765625,"y":391.4880065917969},{"x":678.0411987304688,"y":392.1158142089844},{"x":698.6543579101562,"y":393.0058898925781},{"x":719.1582641601562,"y":393.9601135253906},{"x":739.179931640625,"y":394.6669616699219},{"x":759.0640869140625,"y":395.3464660644531},{"x":635.115478515625,"y":413.9040832519531},{"x":656.3128051757812,"y":414.16644287109375},{"x":677.4334106445312,"y":415.0669250488281},{"x":698.0911254882812,"y":415.8868713378906},{"x":718.63916015625,"y":416.1180114746094},{"x":738.6715087890625,"y":417.0088806152344},{"x":758.2313842773438,"y":417.7875671386719},{"x":634.3212280273438,"y":436.9694519042969},{"x":655.6497802734375,"y":437.10845947265625},{"x":676.3109130859375,"y":437.74090576171875},{"x":697.1973876953125,"y":438.26531982421875},{"x":717.8255004882812,"y":438.8712158203125},{"x":737.9938354492188,"y":439.3226013183594},{"x":757.732421875,"y":440.0768127441406},{"x":633.1463012695312,"y":460.0330505371094},{"x":654.4242553710938,"y":460.2530822753906},{"x":675.4493408203125,"y":461.0587463378906},{"x":696.1884155273438,"y":461.2337646484375},{"x":716.9584350585938,"y":461.78912353515625},{"x":737.077880859375,"y":462.0497741699219},{"x":757.1848754882812,"y":462.3872985839844},{"x":632.2225952148438,"y":483.07745361328125},{"x":653.7341918945312,"y":483.8595886230469},{"x":674.9586791992188,"y":483.8917541503906},{"x":695.8773803710938,"y":484.0645751953125},{"x":716.0153198242188,"y":484.0696716308594},{"x":736.1421508789062,"y":484.6651916503906},{"x":756.3182983398438,"y":484.9635314941406}],"reprojectionErrors":[{"x":-0.06158447265625,"y":0.10858154296875},{"x":0.094482421875,"y":-0.268096923828125},{"x":0.03350830078125,"y":0.112945556640625},{"x":0.21807861328125,"y":-0.120269775390625},{"x":0.42645263671875,"y":-0.079254150390625},{"x":-0.04901123046875,"y":-0.15380859375},{"x":0.20208740234375,"y":0.4552001953125},{"x":0.1319580078125,"y":0.179931640625},{"x":-0.0809326171875,"y":0.006103515625},{"x":-0.0975341796875,"y":0.13873291015625},{"x":0.1280517578125,"y":-0.212982177734375},{"x":0.08624267578125,"y":-0.055389404296875},{"x":0.2529296875,"y":0.11865234375},{"x":0.28033447265625,"y":0.0179443359375},{"x":0.16571044921875,"y":-0.159332275390625},{"x":0.28326416015625,"y":-0.101531982421875},{"x":0.289306640625,"y":-0.028594970703125},{"x":0.23431396484375,"y":-0.1990966796875},{"x":0.2122802734375,"y":0.226043701171875},{"x":0.0130615234375,"y":6.7138671875E-4},{"x":0.02386474609375,"y":-0.15643310546875},{"x":-0.10736083984375,"y":0.26312255859375},{"x":0.02642822265625,"y":0.010894775390625},{"x":0.3831787109375,"y":-0.141082763671875},{"x":0.11541748046875,"y":-0.126434326171875},{"x":-0.00897216796875,"y":0.294525146484375},{"x":0.2796630859375,"y":0.209869384765625},{"x":0.08953857421875,"y":0.221221923828125},{"x":-0.09454345703125,"y":0.13922119140625},{"x":-0.07000732421875,"y":0.199920654296875},{"x":0.13421630859375,"y":-0.05389404296875},{"x":0.369384765625,"y":-0.001708984375},{"x":0.3243408203125,"y":0.210113525390625},{"x":0.27716064453125,"y":-0.175628662109375},{"x":0.26202392578125,"y":0.0574951171875},{"x":-0.036865234375,"y":-0.10137939453125},{"x":0.06304931640625,"y":0.022918701171875},{"x":-0.07513427734375,"y":0.058990478515625},{"x":0.36444091796875,"y":0.191558837890625},{"x":0.11419677734375,"y":-0.287384033203125},{"x":-0.10443115234375,"y":-0.028076171875},{"x":-0.2718505859375,"y":0.07904052734375},{"x":0.08819580078125,"y":0.342498779296875},{"x":0.20703125,"y":0.0042724609375},{"x":0.0255126953125,"y":-0.0478515625}],"optimisedCameraToObject":{"translation":{"x":0.24754713549908436,"y":0.01758448765983381,"z":0.7509637360505108},"rotation":{"quaternion":{"W":0.9959298692199076,"X":-0.014744698700668487,"Y":-0.08468339221670153,"Z":0.027111114667540726}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":447.98565673828125,"y":366.0115051269531},{"x":471.3189392089844,"y":366.892578125},{"x":494.91156005859375,"y":367.2764587402344},{"x":518.9103393554688,"y":367.99835205078125},{"x":542.2122192382812,"y":368.39337158203125},{"x":565.9973754882812,"y":369.1334228515625},{"x":589.6964721679688,"y":370.1134338378906},{"x":447.24810791015625,"y":389.4342041015625},{"x":470.78436279296875,"y":390.0230407714844},{"x":494.425048828125,"y":390.985107421875},{"x":518.0431518554688,"y":391.7659912109375},{"x":541.5393676757812,"y":392.0966796875},{"x":565.402099609375,"y":392.8497009277344},{"x":589.0236206054688,"y":393.3424072265625},{"x":446.2716979980469,"y":412.9163818359375},{"x":470.0987243652344,"y":413.42156982421875},{"x":493.56207275390625,"y":414.0374450683594},{"x":517.07666015625,"y":415.053955078125},{"x":540.9677124023438,"y":415.93798828125},{"x":564.7122192382812,"y":416.229736328125},{"x":588.1357421875,"y":416.99365234375},{"x":445.8376770019531,"y":436.2386779785156},{"x":469.4493103027344,"y":437.2322082519531},{"x":492.94622802734375,"y":437.9151306152344},{"x":516.6016845703125,"y":438.303466796875},{"x":540.1926879882812,"y":439.3043518066406},{"x":563.9985961914062,"y":440.0093078613281},{"x":587.4954223632812,"y":440.4448547363281},{"x":445.2002258300781,"y":459.3562927246094},{"x":468.8190612792969,"y":459.9555358886719},{"x":492.0570983886719,"y":461.02642822265625},{"x":515.9443359375,"y":461.81158447265625},{"x":539.57275390625,"y":462.4569091796875},{"x":562.9671020507812,"y":463.0577392578125},{"x":586.8317260742188,"y":463.97418212890625},{"x":444.7334289550781,"y":482.88525390625},{"x":468.0389099121094,"y":483.9429016113281},{"x":491.6917724609375,"y":484.2176818847656},{"x":515.029541015625,"y":485.1873474121094},{"x":538.8141479492188,"y":485.9776916503906},{"x":562.1469116210938,"y":486.8894958496094},{"x":586.2509155273438,"y":487.6807556152344},{"x":443.9853515625,"y":506.1192932128906},{"x":467.69268798828125,"y":507.0080261230469},{"x":491.01971435546875,"y":507.8973083496094},{"x":514.5439453125,"y":508.4829406738281},{"x":538.0091552734375,"y":509.1659851074219},{"x":561.7861938476562,"y":510.05413818359375},{"x":585.3952026367188,"y":510.97589111328125}],"reprojectionErrors":[{"x":-0.16455078125,"y":-0.012786865234375},{"x":0.06915283203125,"y":-0.227935791015625},{"x":0.087310791015625,"y":0.05126953125},{"x":-0.2606201171875,"y":-0.010498046875},{"x":0.124755859375,"y":0.251556396484375},{"x":0.05950927734375,"y":0.16534423828125},{"x":0.109130859375,"y":-0.16412353515625},{"x":-0.054412841796875,"y":0.0311279296875},{"x":-0.04248046875,"y":0.1317138671875},{"x":-0.09124755859375,"y":-0.144989013671875},{"x":-0.077392578125,"y":-0.244720458984375},{"x":0.09478759765625,"y":0.101470947265625},{"x":-0.06695556640625,"y":0.0208740234375},{"x":0.04132080078125,"y":0.196044921875},{"x":0.29498291015625,"y":-0.022552490234375},{"x":-0.0030517578125,"y":0.18505859375},{"x":0.106353759765625,"y":0.2767333984375},{"x":0.20452880859375,"y":-0.03765869140625},{"x":-0.03741455078125,"y":-0.22509765625},{"x":-0.10028076171875,"y":0.174072265625},{"x":0.186767578125,"y":0.095306396484375},{"x":0.1024169921875,"y":0.04443359375},{"x":2.74658203125E-4,"y":-0.212982177734375},{"x":0.0565185546875,"y":-0.166290283203125},{"x":-0.00579833984375,"y":0.16839599609375},{"x":0.03271484375,"y":-0.116241455078125},{"x":-0.11114501953125,"y":-0.111846923828125},{"x":0.0828857421875,"y":0.15496826171875},{"x":0.113739013671875,"y":0.275848388671875},{"x":-0.0155029296875,"y":0.4359130859375},{"x":0.27972412109375,"y":0.116668701171875},{"x":-0.0343017578125,"y":0.0753173828125},{"x":-0.05322265625,"y":0.16583251953125},{"x":0.1944580078125,"y":0.292724609375},{"x":7.32421875E-4,"y":0.095733642578125},{"x":-0.045135498046875,"y":0.054595947265625},{"x":0.1187744140625,"y":-0.220611572265625},{"x":-0.021087646484375,"y":0.27813720703125},{"x":0.19403076171875,"y":0.072998046875},{"x":-0.00140380859375,"y":0.037994384765625},{"x":0.28753662109375,"y":-0.1278076171875},{"x":-0.16595458984375,"y":-0.182525634765625},{"x":0.07781982421875,"y":0.085906982421875},{"x":-0.18072509765625,"y":0.00262451171875},{"x":-0.015380859375,"y":-0.091278076171875},{"x":-0.00732421875,"y":0.108245849609375},{"x":0.095947265625,"y":0.199951171875},{"x":-0.08013916015625,"y":0.076019287109375},{"x":-0.05938720703125,"y":-0.09222412109375}],"optimisedCameraToObject":{"translation":{"x":0.034122441749156095,"y":0.04029431283328029,"z":0.7354364688351985},"rotation":{"quaternion":{"W":0.99976524130964,"X":0.011462634446365406,"Y":0.013384081574993042,"Z":0.012607007615623483}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img4.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.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":341.9446716308594,"y":338.99041748046875},{"x":365.12640380859375,"y":339.4508361816406},{"x":388.7294616699219,"y":339.88134765625},{"x":412.1387023925781,"y":340.0793151855469},{"x":435.2712707519531,"y":340.35601806640625},{"x":294.0413513183594,"y":361.9755859375},{"x":317.7515869140625,"y":362.07501220703125},{"x":341.30120849609375,"y":362.3594055175781},{"x":365.0148010253906,"y":362.88714599609375},{"x":388.31292724609375,"y":363.0168762207031},{"x":412.0378723144531,"y":363.3788757324219},{"x":435.04156494140625,"y":363.8414611816406},{"x":293.6105041503906,"y":385.682373046875},{"x":317.1171569824219,"y":385.960693359375},{"x":340.89471435546875,"y":385.9474792480469},{"x":364.3169860839844,"y":386.28466796875},{"x":387.9880065917969,"y":386.3755187988281},{"x":411.0895690917969,"y":386.97198486328125},{"x":434.33612060546875,"y":386.9864501953125},{"x":293.20263671875,"y":409.2626647949219},{"x":316.90667724609375,"y":409.6739501953125},{"x":340.19635009765625,"y":409.7577209472656},{"x":364.0110778808594,"y":410.09033203125},{"x":387.60369873046875,"y":410.1377258300781},{"x":410.83807373046875,"y":410.35369873046875},{"x":434.2080993652344,"y":410.4848327636719},{"x":292.97564697265625,"y":432.27581787109375},{"x":316.2349853515625,"y":432.9315490722656},{"x":340.0411682128906,"y":433.0538024902344},{"x":363.7281188964844,"y":433.0025939941406},{"x":387.02880859375,"y":433.3888854980469},{"x":410.2279968261719,"y":433.9454040527344},{"x":433.7293395996094,"y":433.92034912109375},{"x":292.1387023925781,"y":456.2340393066406},{"x":315.9443664550781,"y":456.1676940917969},{"x":339.37628173828125,"y":456.473388671875},{"x":363.09979248046875,"y":456.6989440917969},{"x":386.5052490234375,"y":457.0135192871094},{"x":409.8800964355469,"y":457.0748596191406},{"x":433.2568359375,"y":457.6296691894531},{"x":291.862548828125,"y":480.00738525390625},{"x":315.5344543457031,"y":479.99676513671875},{"x":338.9934387207031,"y":480.0941467285156},{"x":362.78179931640625,"y":480.2334899902344},{"x":386.0271301269531,"y":480.3453063964844},{"x":409.4964599609375,"y":480.4708251953125},{"x":432.8271789550781,"y":480.8829345703125}],"reprojectionErrors":[{"x":-0.20916748046875,"y":-0.027313232421875},{"x":0.15557861328125,"y":-0.11175537109375},{"x":0.018829345703125,"y":-0.16961669921875},{"x":-0.007598876953125,"y":0.001678466796875},{"x":0.155792236328125,"y":0.090789794921875},{"x":-0.052703857421875,"y":-0.13916015625},{"x":-0.0687255859375,"y":0.106781005859375},{"x":0.002593994140625,"y":0.163360595703125},{"x":-0.166778564453125,"y":-0.02783203125},{"x":-8.23974609375E-4,"y":0.174468994140625},{"x":-0.345184326171875,"y":0.140045166015625},{"x":-0.0550537109375,"y":4.8828125E-4},{"x":-0.047637939453125,"y":-0.21826171875},{"x":0.137176513671875,"y":-0.1883544921875},{"x":-0.02215576171875,"y":0.127532958984375},{"x":0.09710693359375,"y":0.087432861328125},{"x":-0.112457275390625,"y":0.2880859375},{"x":0.16400146484375,"y":-0.022491455078125},{"x":0.208709716796875,"y":0.2432861328125},{"x":-0.0643310546875,"y":-0.179473876953125},{"x":-0.080047607421875,"y":-0.31964111328125},{"x":0.245391845703125,"y":-0.1390380859375},{"x":-0.030853271484375,"y":-0.213958740234375},{"x":-0.165008544921875,"y":-0.010406494140625},{"x":-0.024322509765625,"y":0.017852783203125},{"x":-0.105987548828125,"y":0.12420654296875},{"x":-0.260650634765625,"y":0.41668701171875},{"x":0.164794921875,"y":-0.00506591796875},{"x":-0.029754638671875,"y":0.09881591796875},{"x":-0.181640625,"y":0.368316650390625},{"x":-0.02728271484375,"y":0.192474365234375},{"x":0.145233154296875,"y":-0.161468505859375},{"x":-0.071014404296875,"y":0.058349609375},{"x":0.154266357421875,"y":0.05682373046875},{"x":0.029449462890625,"y":0.320068359375},{"x":0.205291748046875,"y":0.2022705078125},{"x":0.013031005859375,"y":0.1556396484375},{"x":0.058837890625,"y":0.011016845703125},{"x":0.052001953125,"y":0.110687255859375},{"x":-0.0433349609375,"y":-0.29205322265625},{"x":0.009674072265625,"y":-0.130279541015625},{"x":0.014312744140625,"y":0.040191650390625},{"x":0.158843994140625,"y":0.092529296875},{"x":-0.102508544921875,"y":0.0927734375},{"x":0.099273681640625,"y":0.110443115234375},{"x":-0.00616455078125,"y":0.1043701171875},{"x":-0.05950927734375,"y":-0.198333740234375}],"optimisedCameraToObject":{"translation":{"x":-0.13134416977800117,"y":0.010323779633028083,"z":0.7308503926451307},"rotation":{"quaternion":{"W":0.9996605905981145,"X":0.0025480876132541507,"Y":-0.024209947028352042,"Z":0.009278433026567359}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":97.61500549316406,"y":336.0641784667969},{"x":120.96920013427734,"y":336.9745788574219},{"x":144.57666015625,"y":337.9964294433594},{"x":168.98252868652344,"y":339.07489013671875},{"x":193.4680633544922,"y":340.1340026855469},{"x":218.22116088867188,"y":341.0326843261719},{"x":243.0047149658203,"y":342.2440185546875},{"x":96.71175384521484,"y":361.75238037109375},{"x":120.14875030517578,"y":363.01373291015625},{"x":144.02333068847656,"y":364.2213134765625},{"x":167.95489501953125,"y":365.3166809082031},{"x":192.05722045898438,"y":366.85107421875},{"x":217.23483276367188,"y":367.7889404296875},{"x":242.24429321289062,"y":369.021484375},{"x":95.8846206665039,"y":387.8974914550781},{"x":119.16228485107422,"y":389.06158447265625},{"x":142.9612579345703,"y":390.18646240234375},{"x":167.1494598388672,"y":391.8658752441406},{"x":191.63900756835938,"y":393.1479187011719},{"x":216.1166229248047,"y":394.6579895019531},{"x":241.18560791015625,"y":395.9226989746094},{"x":94.93936920166016,"y":413.6061096191406},{"x":115.83428192138672,"y":414.9969787597656},{"x":141.81893920898438,"y":416.3804016113281},{"x":165.98773193359375,"y":418.0617980957031},{"x":190.3942108154297,"y":419.70068359375},{"x":214.9544677734375,"y":421.1881103515625},{"x":240.09629821777344,"y":422.9295349121094},{"x":93.96711730957031,"y":439.213623046875},{"x":117.5584716796875,"y":440.8392333984375},{"x":141.13279724121094,"y":442.50592041015625},{"x":165.27101135253906,"y":444.16400146484375},{"x":189.60659790039062,"y":446.014404296875},{"x":214.26260375976562,"y":447.7445373535156},{"x":239.14639282226562,"y":449.69683837890625},{"x":93.1928482055664,"y":465.23236083984375},{"x":116.59505462646484,"y":467.13543701171875},{"x":140.275390625,"y":468.8777770996094},{"x":164.19371032714844,"y":470.8779602050781},{"x":188.3455352783203,"y":472.8445739746094},{"x":213.3333740234375,"y":474.8539123535156},{"x":238.15150451660156,"y":476.9864807128906},{"x":92.7521743774414,"y":490.61322021484375},{"x":115.98404693603516,"y":493.0165710449219},{"x":139.02304077148438,"y":494.95001220703125},{"x":163.232177734375,"y":497.1293640136719},{"x":187.41690063476562,"y":499.2298889160156},{"x":212.11880493164062,"y":501.5762634277344},{"x":237.01295471191406,"y":503.8286437988281}],"reprojectionErrors":[{"x":-0.02103424072265625,"y":0.018890380859375},{"x":-0.04674530029296875,"y":0.102447509765625},{"x":0.0291900634765625,"y":0.08740234375},{"x":-0.334991455078125,"y":0.028717041015625},{"x":-0.41717529296875,"y":0.00238037109375},{"x":-0.401947021484375,"y":0.14959716796875},{"x":-0.0489044189453125,"y":-0.002593994140625},{"x":-0.066864013671875,"y":0.088714599609375},{"x":-0.17259979248046875,"y":0.004302978515625},{"x":-0.3607635498046875,"y":-0.012420654296875},{"x":-0.24737548828125,"y":0.097076416015625},{"x":0.057159423828125,"y":-0.218353271484375},{"x":-0.348358154296875,"y":0.076934814453125},{"x":-0.2171783447265625,"y":0.091796875},{"x":-0.18206787109375,"y":-0.27880859375},{"x":-0.126068115234375,"y":-0.082733154296875},{"x":-0.235992431640625,"y":0.16754150390625},{"x":-0.376373291015625,"y":-0.121612548828125},{"x":-0.4559326171875,"y":0.001800537109375},{"x":-0.1580963134765625,"y":-0.087615966796875},{"x":-0.08282470703125,"y":0.083648681640625},{"x":-0.17237091064453125,"y":-0.191619873046875},{"x":2.2684326171875,"y":-0.038848876953125},{"x":-0.0249176025390625,"y":0.137451171875},{"x":-0.143402099609375,"y":0.031951904296875},{"x":-0.1371917724609375,"y":-0.0147705078125},{"x":0.080963134765625,"y":0.106231689453125},{"x":0.0865631103515625,"y":-0.010406494140625},{"x":-0.12882232666015625,"y":0.0135498046875},{"x":-0.382781982421875,"y":0.115264892578125},{"x":-0.263916015625,"y":0.193084716796875},{"x":-0.3497314453125,"y":0.296783447265625},{"x":-0.27032470703125,"y":0.225494384765625},{"x":-0.1453857421875,"y":0.29180908203125},{"x":0.1210174560546875,"y":0.153350830078125},{"x":-0.27634429931640625,"y":-0.177001953125},{"x":-0.33985137939453125,"y":-0.168853759765625},{"x":-0.3254852294921875,"y":0.018341064453125},{"x":-0.1897125244140625,"y":-0.03399658203125},{"x":0.07537841796875,"y":-0.03436279296875},{"x":-0.1294097900390625,"y":-0.05902099609375},{"x":0.2049713134765625,"y":-0.188446044921875},{"x":-0.7505111694335938,"y":0.28448486328125},{"x":-0.642730712890625,"y":-0.0235595703125},{"x":0.01409912109375,"y":0.15771484375},{"x":-0.139617919921875,"y":0.11248779296875},{"x":0.0940704345703125,"y":0.16558837890625},{"x":0.176910400390625,"y":-0.0076904296875},{"x":0.4371795654296875,"y":-0.067474365234375}],"optimisedCameraToObject":{"translation":{"x":-0.31634823929517963,"y":0.005004095891901554,"z":0.6773106464321457},"rotation":{"quaternion":{"W":0.9956302433989785,"X":-0.006336032326604208,"Y":0.09186517925814541,"Z":0.0155261702784586}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img6.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.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":179.23895263671875,"y":156.03054809570312},{"x":206.84190368652344,"y":157.575927734375},{"x":233.7938232421875,"y":159.07339477539062},{"x":260.92828369140625,"y":160.43203735351562},{"x":287.8433837890625,"y":162.00180053710938},{"x":124.97286987304688,"y":180.41293334960938},{"x":152.35006713867188,"y":181.77638244628906},{"x":179.15428161621094,"y":183.2238311767578},{"x":206.3820037841797,"y":185.00515747070312},{"x":233.23191833496094,"y":186.0235137939453},{"x":260.3642578125,"y":187.92788696289062},{"x":287.0011291503906,"y":189.0528106689453},{"x":125.74578857421875,"y":207.88568115234375},{"x":152.55030822753906,"y":209.0631561279297},{"x":179.2863311767578,"y":210.15814208984375},{"x":206.33233642578125,"y":211.95249938964844},{"x":233.13067626953125,"y":213.15518188476562},{"x":259.935546875,"y":214.81695556640625},{"x":286.2164001464844,"y":215.9636688232422},{"x":125.94800567626953,"y":234.4815673828125},{"x":152.9366912841797,"y":235.94944763183594},{"x":179.3036346435547,"y":237.1339874267578},{"x":206.16748046875,"y":238.9255828857422},{"x":232.71083068847656,"y":239.97129821777344},{"x":259.2073669433594,"y":241.254638671875},{"x":285.5835876464844,"y":242.48013305664062},{"x":126.11270141601562,"y":260.6037292480469},{"x":152.958984375,"y":261.9674987792969},{"x":179.239990234375,"y":263.461181640625},{"x":206.18199157714844,"y":264.637939453125},{"x":232.71420288085938,"y":265.9879455566406},{"x":259.0379638671875,"y":267.2241516113281},{"x":284.8939514160156,"y":268.3166809082031},{"x":126.67525482177734,"y":286.9856262207031},{"x":153.09518432617188,"y":288.2422790527344},{"x":179.4561309814453,"y":289.4141540527344},{"x":206.04443359375,"y":290.98602294921875},{"x":231.97097778320312,"y":292.051513671875},{"x":258.12689208984375,"y":293.20037841796875},{"x":284.2055358886719,"y":294.75848388671875},{"x":126.91804504394531,"y":312.7438049316406},{"x":153.3087158203125,"y":314.0313720703125},{"x":179.20553588867188,"y":315.157470703125},{"x":205.6704559326172,"y":316.26654052734375},{"x":231.98622131347656,"y":317.78912353515625},{"x":257.77471923828125,"y":318.8023681640625},{"x":283.75274658203125,"y":319.9034423828125}],"reprojectionErrors":[{"x":0.0879974365234375,"y":-0.060394287109375},{"x":-0.28436279296875,"y":-0.1079864501953125},{"x":-0.0784454345703125,"y":-0.11053466796875},{"x":-0.132415771484375,"y":0.0225982666015625},{"x":-0.048919677734375,"y":-0.0587615966796875},{"x":0.07080841064453125,"y":0.082489013671875},{"x":-0.128143310546875,"y":0.174102783203125},{"x":0.18341064453125,"y":0.1778564453125},{"x":0.0043487548828125,"y":-0.1563873291015625},{"x":0.1313934326171875,"y":0.26800537109375},{"x":-0.1002197265625,"y":-0.1982269287109375},{"x":0.0828857421875,"y":0.11016845703125},{"x":-0.3250885009765625,"y":-0.229156494140625},{"x":-0.1332550048828125,"y":0.0018463134765625},{"x":0.065521240234375,"y":0.30999755859375},{"x":-0.111846923828125,"y":-0.0867767333984375},{"x":-0.1121978759765625,"y":0.102325439453125},{"x":-0.194244384765625,"y":-0.1736907958984375},{"x":0.168121337890625,"y":0.05914306640625},{"x":-0.1507720947265625,"y":-0.0254364013671875},{"x":-0.32305908203125,"y":-0.1303558349609375},{"x":0.0657196044921875,"y":0.0413055419921875},{"x":-0.10760498046875,"y":-0.4010772705078125},{"x":-0.03009033203125,"y":-0.104766845703125},{"x":0.0201416015625,"y":-0.0534820556640625},{"x":0.11224365234375,"y":0.04803466796875},{"x":0.060577392578125,"y":0.29620361328125},{"x":-0.1473846435546875,"y":0.250946044921875},{"x":0.150146484375,"y":0.067626953125},{"x":-0.277587890625,"y":0.192840576171875},{"x":-0.36419677734375,"y":0.136260986328125},{"x":-0.3154296875,"y":0.184722900390625},{"x":0.123779296875,"y":0.367950439453125},{"x":-0.12644195556640625,"y":0.0079345703125},{"x":-0.0842437744140625,"y":0.0263671875},{"x":-0.0420074462890625,"y":0.12005615234375},{"x":-0.29046630859375,"y":-0.195953369140625},{"x":0.055145263671875,"y":-0.015472412109375},{"x":0.099365234375,"y":0.071533203125},{"x":0.144561767578125,"y":-0.260894775390625},{"x":0.00579071044921875,"y":-0.0013427734375},{"x":-0.0971221923828125,"y":-0.056243896484375},{"x":0.2357330322265625,"y":0.03948974609375},{"x":-0.06195068359375,"y":0.141204833984375},{"x":-0.2772216796875,"y":-0.1817626953125},{"x":-0.0362548828125,"y":-0.006744384765625},{"x":-0.060028076171875,"y":0.068939208984375}],"optimisedCameraToObject":{"translation":{"x":-0.2760527131762726,"y":-0.16813565080691012,"z":0.6330842627409643},"rotation":{"quaternion":{"W":0.9958270942445676,"X":0.0861069674245715,"Y":-0.01674666803319107,"Z":0.02517017360192109}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":57.41508102416992,"y":156.19703674316406},{"x":88.99311828613281,"y":157.35690307617188},{"x":119.76762390136719,"y":158.71072387695312},{"x":149.94705200195312,"y":160.00352478027344},{"x":179.50148010253906,"y":161.0408172607422},{"x":208.46078491210938,"y":162.5142059326172},{"x":236.79595947265625,"y":163.6628875732422},{"x":58.5984001159668,"y":185.36453247070312},{"x":89.9607925415039,"y":186.656982421875},{"x":120.48433685302734,"y":187.71035766601562},{"x":150.64244079589844,"y":188.2244873046875},{"x":179.9647216796875,"y":189.1368408203125},{"x":208.9032745361328,"y":190.31033325195312},{"x":236.91464233398438,"y":191.21859741210938},{"x":59.5854606628418,"y":214.94866943359375},{"x":90.7377700805664,"y":215.4237823486328},{"x":121.02872467041016,"y":216.00228881835938},{"x":151.19020080566406,"y":216.80926513671875},{"x":180.44345092773438,"y":217.26138305664062},{"x":209.03707885742188,"y":217.996337890625},{"x":237.1096954345703,"y":218.5461883544922},{"x":60.847633361816406,"y":243.88116455078125},{"x":91.74215698242188,"y":243.96539306640625},{"x":122.04385375976562,"y":244.24766540527344},{"x":151.85208129882812,"y":244.97593688964844},{"x":180.99331665039062,"y":245.09634399414062},{"x":209.54660034179688,"y":245.72637939453125},{"x":237.21009826660156,"y":245.82479858398438},{"x":61.71562194824219,"y":272.03814697265625},{"x":92.52717590332031,"y":272.0182189941406},{"x":122.6902084350586,"y":272.0984802246094},{"x":152.42367553710938,"y":272.17254638671875},{"x":181.26165771484375,"y":272.3561706542969},{"x":209.96560668945312,"y":272.5198669433594},{"x":237.74310302734375,"y":272.65740966796875},{"x":62.60470199584961,"y":300.67266845703125},{"x":93.18622589111328,"y":300.3593444824219},{"x":123.37718200683594,"y":300.1873779296875},{"x":152.89686584472656,"y":299.9823913574219},{"x":181.74166870117188,"y":299.9992370605469},{"x":210.09332275390625,"y":299.8036804199219},{"x":237.92066955566406,"y":299.5470886230469},{"x":63.69561767578125,"y":328.34100341796875},{"x":94.06459045410156,"y":327.9868469238281},{"x":123.91429901123047,"y":327.7765197753906},{"x":153.45877075195312,"y":327.0889587402344},{"x":182.05250549316406,"y":326.84765625},{"x":210.35548400878906,"y":326.0143127441406},{"x":238.03480529785156,"y":325.7134094238281}],"reprojectionErrors":[{"x":0.1119842529296875,"y":-0.3919219970703125},{"x":0.02770233154296875,"y":-0.214111328125},{"x":0.07772064208984375,"y":-0.2551116943359375},{"x":0.069244384765625,"y":-0.259429931640625},{"x":0.0474853515625,"y":-0.0319976806640625},{"x":-0.002593994140625,"y":-0.2639312744140625},{"x":-0.037567138671875,"y":-0.19390869140625},{"x":-0.008991241455078125,"y":0.012451171875},{"x":-0.04515838623046875,"y":-0.2676544189453125},{"x":0.09510040283203125,"y":-0.328277587890625},{"x":-0.0462188720703125,"y":0.13116455078125},{"x":0.0162811279296875,"y":0.1736297607421875},{"x":-0.1548919677734375,"y":-0.0633544921875},{"x":-0.0020599365234375,"y":-0.0530242919921875},{"x":0.058612823486328125,"y":-0.2945556640625},{"x":0.06613922119140625,"y":-0.0762939453125},{"x":0.27931976318359375,"y":0.0240631103515625},{"x":-0.0185699462890625,"y":-0.1182403564453125},{"x":-0.03399658203125,"y":0.0804595947265625},{"x":-0.001220703125,"y":-0.0172271728515625},{"x":-0.04486083984375,"y":0.0569610595703125},{"x":-0.15651702880859375,"y":-0.2419586181640625},{"x":-0.05646514892578125,"y":0.0544586181640625},{"x":-0.01263427734375,"y":0.1432647705078125},{"x":-0.1094818115234375,"y":-0.2233123779296875},{"x":-0.1589508056640625,"y":0.0088653564453125},{"x":-0.2259674072265625,"y":-0.2775115966796875},{"x":0.00506591796875,"y":-0.04095458984375},{"x":0.01496124267578125,"y":0.29681396484375},{"x":0.033843994140625,"y":0.390838623046875},{"x":0.05877685546875,"y":0.37982177734375},{"x":-0.1145477294921875,"y":0.370330810546875},{"x":-0.0059051513671875,"y":0.246734619140625},{"x":-0.3628692626953125,"y":0.13861083984375},{"x":-0.379486083984375,"y":0.0523681640625},{"x":0.15783309936523438,"y":0.071380615234375},{"x":0.24372100830078125,"y":0.15826416015625},{"x":0.0842132568359375,"y":0.10357666015625},{"x":-0.0255889892578125,"y":0.08172607421875},{"x":-0.068023681640625,"y":-0.16204833984375},{"x":-0.2111358642578125,"y":-0.193511962890625},{"x":-0.4104766845703125,"y":-0.16400146484375},{"x":0.09140396118164062,"y":0.528106689453125},{"x":0.22792816162109375,"y":0.36126708984375},{"x":0.25417327880859375,"y":0.0548095703125},{"x":-0.0297088623046875,"y":0.22979736328125},{"x":0.03558349609375,"y":-0.037322998046875},{"x":-0.1964874267578125,"y":0.291748046875},{"x":-0.3798828125,"y":0.09246826171875}],"optimisedCameraToObject":{"translation":{"x":-0.31682738866197047,"y":-0.15442123887700634,"z":0.5837741642520742},"rotation":{"quaternion":{"W":0.9896064788088634,"X":0.060269292242198874,"Y":-0.13052865213700213,"Z":0.0029833678023946995}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":121.498291015625,"y":53.990806579589844},{"x":152.80255126953125,"y":56.918514251708984},{"x":182.77249145507812,"y":60.02717590332031},{"x":212.13917541503906,"y":63.19260025024414},{"x":241.0860595703125,"y":66.34115600585938},{"x":269.3520202636719,"y":69.32079315185547},{"x":296.61553955078125,"y":72.13152313232422},{"x":122.40913391113281,"y":84.04911041259766},{"x":152.94232177734375,"y":87.03606414794922},{"x":182.64622497558594,"y":89.82044982910156},{"x":211.99856567382812,"y":92.87154388427734},{"x":240.2277069091797,"y":95.26178741455078},{"x":268.3757019042969,"y":98.13613891601562},{"x":295.08251953125,"y":100.46299743652344},{"x":122.9631576538086,"y":114.066650390625},{"x":153.1135711669922,"y":116.20465087890625},{"x":182.8377685546875,"y":118.85829162597656},{"x":211.72305297851562,"y":121.32259368896484},{"x":239.81072998046875,"y":123.81327056884766},{"x":267.23480224609375,"y":126.0376205444336},{"x":294.04949951171875,"y":128.16526794433594},{"x":123.73482513427734,"y":143.07183837890625},{"x":153.5081024169922,"y":145.32656860351562},{"x":182.72732543945312,"y":147.56631469726562},{"x":211.32582092285156,"y":149.5387725830078},{"x":239.15919494628906,"y":151.69857788085938},{"x":266.5666809082031,"y":153.849853515625},{"x":292.94976806640625,"y":155.68409729003906},{"x":124.13727569580078,"y":171.1220245361328},{"x":153.74205017089844,"y":173.11196899414062},{"x":182.71836853027344,"y":174.9853057861328},{"x":211.1621856689453,"y":176.79493713378906},{"x":238.49862670898438,"y":178.4734649658203},{"x":265.8219299316406,"y":179.92453002929688},{"x":291.9144592285156,"y":181.8324432373047},{"x":124.96066284179688,"y":199.2381591796875},{"x":154.14083862304688,"y":200.70486450195312},{"x":182.53627014160156,"y":202.15652465820312},{"x":211.05850219726562,"y":203.87747192382812},{"x":238.02357482910156,"y":205.3922119140625},{"x":264.8962707519531,"y":206.5952911376953},{"x":290.74957275390625,"y":207.96823120117188},{"x":125.76335144042969,"y":226.06118774414062},{"x":154.38156127929688,"y":227.59100341796875},{"x":182.76058959960938,"y":228.87582397460938},{"x":210.5233612060547,"y":229.92601013183594},{"x":237.17413330078125,"y":230.9891815185547},{"x":263.8055419921875,"y":231.99871826171875},{"x":289.68231201171875,"y":233.29197692871094}],"reprojectionErrors":[{"x":0.40013885498046875,"y":-0.13199615478515625},{"x":-0.1141510009765625,"y":0.092437744140625},{"x":0.053436279296875,"y":0.07014083862304688},{"x":0.1871337890625,"y":-0.073150634765625},{"x":0.1184234619140625,"y":-0.2623138427734375},{"x":0.122894287109375,"y":-0.34384918212890625},{"x":0.5361328125,"y":-0.31635284423828125},{"x":0.173309326171875,"y":0.34326171875},{"x":0.0511627197265625,"y":0.14636993408203125},{"x":0.1215972900390625,"y":0.09288787841796875},{"x":-0.078369140625,"y":-0.2850799560546875},{"x":0.2371826171875,"y":-0.0586395263671875},{"x":0.040130615234375,"y":-0.3714599609375},{"x":0.704071044921875,"y":-0.19066619873046875},{"x":0.28850555419921875,"y":0.12259674072265625},{"x":0.1788482666015625,"y":0.42889404296875},{"x":-0.126068115234375,"y":0.16655731201171875},{"x":-0.1994171142578125,"y":0.04180145263671875},{"x":-0.068756103515625,"y":-0.1598968505859375},{"x":0.145294189453125,"y":-0.14469146728515625},{"x":0.40155029296875,"y":-0.0810546875},{"x":0.17177581787109375,"y":0.2023162841796875},{"x":0.07733154296875,"y":0.0616302490234375},{"x":-0.06982421875,"y":-0.111328125},{"x":-0.189483642578125,"y":-0.063140869140625},{"x":-0.1239776611328125,"y":-0.247406005859375},{"x":-0.19970703125,"y":-0.467193603515625},{"x":0.19439697265625,"y":-0.4130096435546875},{"x":0.41043853759765625,"y":0.5487518310546875},{"x":0.130645751953125,"y":0.357330322265625},{"x":-0.113250732421875,"y":0.2406005859375},{"x":-0.4041748046875,"y":0.14666748046875},{"x":-0.154541015625,"y":0.1438446044921875},{"x":-0.446197509765625,"y":0.3294219970703125},{"x":-0.049407958984375,"y":0.0199737548828125},{"x":0.21479034423828125,"y":0.163543701171875},{"x":0.013580322265625,"y":0.19384765625},{"x":0.0182647705078125,"y":0.2022705078125},{"x":-0.6701507568359375,"y":-0.0946502685546875},{"x":-0.35546875,"y":-0.2205810546875},{"x":-0.490570068359375,"y":-0.069244384765625},{"x":-0.136749267578125,"y":-0.1213836669921875},{"x":0.02690887451171875,"y":0.427398681640625},{"x":0.0491943359375,"y":0.1063995361328125},{"x":-0.254913330078125,"y":-0.0018768310546875},{"x":-0.496246337890625,"y":0.09295654296875},{"x":-0.167327880859375,"y":0.14404296875},{"x":-0.349273681640625,"y":0.218719482421875},{"x":-0.295654296875,"y":-0.019683837890625}],"optimisedCameraToObject":{"translation":{"x":-0.2589255119836698,"y":-0.2427933664565841,"z":0.5794595409873905},"rotation":{"quaternion":{"W":0.9799898600304914,"X":0.15112811622543043,"Y":-0.12665594043243533,"Z":0.027174242891865284}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img9.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.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":368.96942138671875,"y":65.91423034667969},{"x":394.7527160644531,"y":68.37458801269531},{"x":420.1780090332031,"y":71.0488510131836},{"x":445.78509521484375,"y":73.36840057373047},{"x":470.6046447753906,"y":75.95154571533203},{"x":314.7372131347656,"y":88.21711730957031},{"x":341.0360412597656,"y":90.98574829101562},{"x":366.9888000488281,"y":93.33760070800781},{"x":392.5150146484375,"y":95.95301055908203},{"x":418.0399475097656,"y":98.00727081298828},{"x":443.07025146484375,"y":100.13579559326172},{"x":467.89703369140625,"y":102.49778747558594},{"x":313.11602783203125,"y":115.67381286621094},{"x":339.1872863769531,"y":117.75653839111328},{"x":364.7945861816406,"y":120.06047058105469},{"x":390.2063293457031,"y":122.28267669677734},{"x":415.67510986328125,"y":124.62423706054688},{"x":440.2027282714844,"y":126.98479461669922},{"x":464.5322570800781,"y":128.86172485351562},{"x":312.06475830078125,"y":142.3632049560547},{"x":337.8204650878906,"y":144.66485595703125},{"x":363.01287841796875,"y":146.4701690673828},{"x":388.13897705078125,"y":148.6481475830078},{"x":412.9828796386719,"y":150.8267059326172},{"x":437.5090637207031,"y":152.89230346679688},{"x":461.7171325683594,"y":154.56932067871094},{"x":310.88775634765625,"y":167.99945068359375},{"x":336.168212890625,"y":170.04751586914062},{"x":361.23297119140625,"y":171.98519897460938},{"x":386.1593933105469,"y":173.76931762695312},{"x":410.58807373046875,"y":175.82652282714844},{"x":434.97796630859375,"y":177.66421508789062},{"x":459.1220703125,"y":179.35121154785156},{"x":309.3921813964844,"y":193.74652099609375},{"x":334.4606018066406,"y":195.2259063720703},{"x":359.1919250488281,"y":197.087646484375},{"x":384.038818359375,"y":199.06268310546875},{"x":408.24017333984375,"y":200.8028564453125},{"x":432.36810302734375,"y":202.51919555664062},{"x":456.02386474609375,"y":204.09336853027344},{"x":308.0807189941406,"y":218.32484436035156},{"x":333.08843994140625,"y":219.972412109375},{"x":357.6921691894531,"y":221.58998107910156},{"x":381.98858642578125,"y":223.1558380126953},{"x":406.2618408203125,"y":224.88003540039062},{"x":429.88946533203125,"y":226.60678100585938},{"x":453.58502197265625,"y":228.1021270751953}],"reprojectionErrors":[{"x":-0.04827880859375,"y":0.08437347412109375},{"x":0.0743408203125,"y":0.17273712158203125},{"x":0.270111083984375,"y":0.02104949951171875},{"x":-3.96728515625E-4,"y":0.1979217529296875},{"x":0.23248291015625,"y":0.08506011962890625},{"x":0.07769775390625,"y":0.3311920166015625},{"x":-0.025360107421875,"y":-0.01139068603515625},{"x":-0.061431884765625,"y":0.037261962890625},{"x":0.05010986328125,"y":-0.20317840576171875},{"x":-0.115875244140625,"y":0.09200286865234375},{"x":-0.065765380859375,"y":0.28741455078125},{"x":-0.09033203125,"y":0.223876953125},{"x":0.290802001953125,"y":-2.0599365234375E-4},{"x":0.14031982421875,"y":0.17504119873046875},{"x":0.18072509765625,"y":0.1040802001953125},{"x":0.14361572265625,"y":0.08985137939453125},{"x":-0.22344970703125,"y":-0.0686798095703125},{"x":0.077911376953125,"y":-0.2711334228515625},{"x":0.304931640625,"y":-0.01483154296875},{"x":-0.035888671875,"y":-0.1466522216796875},{"x":-0.140533447265625,"y":-0.351837158203125},{"x":0.05084228515625,"y":-0.085205078125},{"x":0.04119873046875,"y":-0.2157135009765625},{"x":0.0465087890625,"y":-0.371246337890625},{"x":0.102447509765625,"y":-0.438201904296875},{"x":0.20965576171875,"y":-0.1408843994140625},{"x":-0.2076416015625,"y":0.1949462890625},{"x":-0.10162353515625,"y":0.088104248046875},{"x":-0.04156494140625,"y":0.0675811767578125},{"x":-0.104949951171875,"y":0.1765899658203125},{"x":0.067718505859375,"y":-0.011444091796875},{"x":0.017547607421875,"y":-0.00384521484375},{"x":-0.048248291015625,"y":0.1306304931640625},{"x":-0.032501220703125,"y":-0.1228790283203125},{"x":0.025970458984375,"y":0.189727783203125},{"x":0.165313720703125,"y":0.0963134765625},{"x":-0.067291259765625,"y":-0.134002685546875},{"x":0.089324951171875,"y":-0.152984619140625},{"x":0.06304931640625,"y":-0.1715545654296875},{"x":0.2528076171875,"y":-0.0713043212890625},{"x":-0.013946533203125,"y":0.1953887939453125},{"x":-0.149505615234375,"y":0.196319580078125},{"x":-0.132049560546875,"y":0.203948974609375},{"x":-0.058380126953125,"y":0.2400665283203125},{"x":-0.212677001953125,"y":0.0947113037109375},{"x":0.02752685546875,"y":-0.076202392578125},{"x":-0.051239013671875,"y":-0.03863525390625}],"optimisedCameraToObject":{"translation":{"x":-0.096837737680499,"y":-0.25878002721351046,"z":0.6416849956469183},"rotation":{"quaternion":{"W":0.9863494172504824,"X":0.14672803691539432,"Y":-0.06638197767952948,"Z":0.03433865623379574}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":524.0452880859375,"y":49.90778350830078},{"x":548.7825317382812,"y":51.85581970214844},{"x":573.2677612304688,"y":53.88032531738281},{"x":598.1990356445312,"y":55.99870681762695},{"x":622.95849609375,"y":57.948421478271484},{"x":647.7489013671875,"y":59.852638244628906},{"x":672.5323486328125,"y":62.127445220947266},{"x":520.9467163085938,"y":75.27804565429688},{"x":544.95703125,"y":77.77095031738281},{"x":569.5671997070312,"y":79.86370086669922},{"x":594.2412109375,"y":81.78543853759766},{"x":618.8273315429688,"y":83.9392318725586},{"x":643.5252075195312,"y":86.03004455566406},{"x":668.039306640625,"y":87.96307373046875},{"x":517.3387451171875,"y":100.85692596435547},{"x":541.7862548828125,"y":102.91368865966797},{"x":565.7620849609375,"y":105.14532470703125},{"x":590.145263671875,"y":107.07211303710938},{"x":614.6468505859375,"y":108.95285034179688},{"x":639.0621948242188,"y":111.45539093017578},{"x":663.558837890625,"y":113.44426727294922},{"x":514.1788330078125,"y":125.99434661865234},{"x":538.1118774414062,"y":128.0659942626953},{"x":562.1294555664062,"y":130.11351013183594},{"x":586.357666015625,"y":132.17626953125},{"x":610.55517578125,"y":134.09750366210938},{"x":634.9482421875,"y":136.2822265625},{"x":659.05615234375,"y":138.57904052734375},{"x":511.08636474609375,"y":150.25636291503906},{"x":534.8436889648438,"y":151.9950408935547},{"x":558.8811645507812,"y":154.31716918945312},{"x":582.5707397460938,"y":156.5441131591797},{"x":606.7430419921875,"y":158.36708068847656},{"x":630.9149169921875,"y":160.6362762451172},{"x":654.8162231445312,"y":162.92947387695312},{"x":507.9510498046875,"y":174.54354858398438},{"x":531.57568359375,"y":176.43170166015625},{"x":555.1544799804688,"y":178.55892944335938},{"x":578.988525390625,"y":180.92955017089844},{"x":602.6702270507812,"y":182.96897888183594},{"x":626.5747680664062,"y":185.0165557861328},{"x":650.6617431640625,"y":187.2545166015625},{"x":504.9621887207031,"y":197.81924438476562},{"x":528.2085571289062,"y":200.1539306640625},{"x":551.8722534179688,"y":202.26214599609375},{"x":575.1571655273438,"y":204.21932983398438},{"x":599.0906372070312,"y":206.48681640625},{"x":622.7322998046875,"y":208.94635009765625},{"x":646.386474609375,"y":210.84791564941406}],"reprojectionErrors":[{"x":-0.201416015625,"y":-0.21646881103515625},{"x":-0.265625,"y":-0.116241455078125},{"x":-0.0078125,"y":-0.08187103271484375},{"x":-0.12969970703125,"y":-0.1310577392578125},{"x":-0.0172119140625,"y":-0.00154876708984375},{"x":0.12298583984375,"y":0.1831817626953125},{"x":0.324951171875,"y":0.006744384765625},{"x":-0.35345458984375,"y":0.22519683837890625},{"x":0.08233642578125,"y":-0.1977996826171875},{"x":-0.01287841796875,"y":-0.211456298828125},{"x":-0.106689453125,"y":-0.0452117919921875},{"x":-0.051025390625,"y":-0.10243988037109375},{"x":-0.0494384765625,"y":-0.088409423828125},{"x":0.18994140625,"y":0.0913848876953125},{"x":0.06048583984375,"y":-7.32421875E-4},{"x":-0.16412353515625,"y":0.032928466796875},{"x":0.15069580078125,"y":-0.10047149658203125},{"x":0.122314453125,"y":0.07846832275390625},{"x":0.0361328125,"y":0.31066131591796875},{"x":0.093017578125,"y":-0.0720672607421875},{"x":0.1217041015625,"y":0.0654296875},{"x":0.08160400390625,"y":-0.233245849609375},{"x":0.15185546875,"y":-0.19503021240234375},{"x":0.20428466796875,"y":-0.1262054443359375},{"x":0.1092529296875,"y":-0.0664825439453125},{"x":0.1044921875,"y":0.1406402587890625},{"x":-0.03985595703125,"y":0.08978271484375},{"x":0.1531982421875,"y":-0.0679473876953125},{"x":0.089202880859375,"y":-0.0277862548828125},{"x":0.119140625,"y":0.3618011474609375},{"x":-0.06536865234375,"y":0.1731109619140625},{"x":0.16009521484375,"y":0.08447265625},{"x":-0.0384521484375,"y":0.40435791015625},{"x":-0.18145751953125,"y":0.2822418212890625},{"x":-0.00244140625,"y":0.1400299072265625},{"x":0.192291259765625,"y":-0.274688720703125},{"x":0.14239501953125,"y":-0.0171661376953125},{"x":0.20294189453125,"y":0.0052032470703125},{"x":0.0694580078125,"y":-0.2122039794921875},{"x":0.14605712890625,"y":-0.0951385498046875},{"x":0.05401611328125,"y":0.0167388916015625},{"x":-0.169677734375,"y":-0.0591278076171875},{"x":0.20037841796875,"y":0.07269287109375},{"x":0.319580078125,"y":-0.0998687744140625},{"x":0.0850830078125,"y":-0.043243408203125},{"x":0.28961181640625,"y":0.16680908203125},{"x":-0.0975341796875,"y":0.0686187744140625},{"x":-0.1395263671875,"y":-0.2198638916015625},{"x":-0.14404296875,"y":0.051025390625}],"optimisedCameraToObject":{"translation":{"x":0.11180230078923507,"y":-0.2899533474899091,"z":0.6979758686890563},"rotation":{"quaternion":{"W":0.9906162757454453,"X":0.1258582013803331,"Y":0.02622597805862725,"Z":0.046382167353411295}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":569.9073486328125,"y":73.99394226074219},{"x":593.7904663085938,"y":73.92759704589844},{"x":617.990966796875,"y":73.24340057373047},{"x":643.0416259765625,"y":73.14846801757812},{"x":668.4610595703125,"y":72.73075866699219},{"x":694.3900146484375,"y":72.2044677734375},{"x":720.5175170898438,"y":72.14366912841797},{"x":568.0505981445312,"y":98.00820922851562},{"x":591.8472900390625,"y":97.92613220214844},{"x":615.986572265625,"y":97.81549835205078},{"x":640.8120727539062,"y":97.73292541503906},{"x":665.9505615234375,"y":97.5985336303711},{"x":691.6508178710938,"y":97.54235076904297},{"x":717.8319702148438,"y":97.50757598876953},{"x":565.9100952148438,"y":121.66460418701172},{"x":589.5657958984375,"y":122.00975036621094},{"x":613.7761840820312,"y":121.93992614746094},{"x":638.0863647460938,"y":122.02753448486328},{"x":663.0403442382812,"y":122.1830062866211},{"x":688.5869140625,"y":122.5542984008789},{"x":714.6636352539062,"y":122.8083267211914},{"x":563.9707641601562,"y":145.3894805908203},{"x":587.3191528320312,"y":145.67210388183594},{"x":611.2584228515625,"y":145.91616821289062},{"x":635.7897338867188,"y":146.11669921875},{"x":660.3165893554688,"y":146.7986602783203},{"x":686.0416259765625,"y":147.0889892578125},{"x":711.6866455078125,"y":147.6366729736328},{"x":562.1524658203125,"y":167.92236328125},{"x":585.6284790039062,"y":168.77854919433594},{"x":608.9248046875,"y":169.30848693847656},{"x":633.28759765625,"y":169.87631225585938},{"x":658.009521484375,"y":170.32583618164062},{"x":683.282470703125,"y":171.13014221191406},{"x":708.7063598632812,"y":171.9752197265625},{"x":560.1513061523438,"y":191.0990447998047},{"x":583.4462890625,"y":191.87060546875},{"x":606.9073486328125,"y":192.7923126220703},{"x":631.0411376953125,"y":193.55857849121094},{"x":655.4586791992188,"y":194.24212646484375},{"x":680.503662109375,"y":195.13235473632812},{"x":706.0552368164062,"y":196.1321258544922},{"x":558.7040405273438,"y":213.17831420898438},{"x":581.2661743164062,"y":214.52236938476562},{"x":604.6900024414062,"y":215.52694702148438},{"x":628.9173583984375,"y":216.232177734375},{"x":653.1513671875,"y":217.75714111328125},{"x":677.8412475585938,"y":218.7955322265625},{"x":702.9755249023438,"y":219.9374542236328}],"reprojectionErrors":[{"x":-0.2523193359375,"y":-0.05484771728515625},{"x":-0.2550048828125,"y":-0.28891754150390625},{"x":-0.06915283203125,"y":0.09384918212890625},{"x":-0.21514892578125,"y":-0.11365509033203125},{"x":-0.19873046875,"y":6.256103515625E-4},{"x":-0.14752197265625,"y":0.22251129150390625},{"x":0.26318359375,"y":-0.0220489501953125},{"x":-0.2667236328125,"y":-0.1227874755859375},{"x":-0.35626220703125,"y":-0.08994293212890625},{"x":-0.289306640625,"y":-0.02548980712890625},{"x":-0.39739990234375,"y":0.01406097412109375},{"x":-0.29461669921875,"y":0.1086883544921875},{"x":-0.2169189453125,"y":0.12847900390625},{"x":-0.07012939453125,"y":0.1303558349609375},{"x":0.02716064453125,"y":-0.13533782958984375},{"x":-0.09259033203125,"y":-0.284881591796875},{"x":-0.27459716796875,"y":-0.01250457763671875},{"x":-0.0521240234375,"y":0.10958099365234375},{"x":0.04302978515625,"y":0.171142578125},{"x":0.0748291015625,"y":0.02442169189453125},{"x":0.11859130859375,"y":0.00270843505859375},{"x":0.14404296875,"y":-0.5141754150390625},{"x":0.16253662109375,"y":-0.362548828125},{"x":0.07598876953125,"y":-0.16168212890625},{"x":-0.105224609375,"y":0.09368896484375},{"x":0.22747802734375,"y":-0.1211395263671875},{"x":-0.1162109375,"y":0.0671844482421875},{"x":0.15460205078125,"y":0.0099639892578125},{"x":0.16363525390625,"y":0.005767822265625},{"x":-0.11248779296875,"y":-0.183563232421875},{"x":0.2703857421875,"y":-0.0323638916015625},{"x":0.0775146484375,"y":0.095550537109375},{"x":0.0279541015625,"y":0.3567352294921875},{"x":-0.05810546875,"y":0.278472900390625},{"x":0.23187255859375,"y":0.1751251220703125},{"x":0.38958740234375,"y":-0.4068145751953125},{"x":0.12945556640625,"y":-0.2847900390625},{"x":0.17620849609375,"y":-0.2952117919921875},{"x":0.03436279296875,"y":-0.132080078125},{"x":0.10443115234375,"y":0.1323089599609375},{"x":0.05438232421875,"y":0.208984375},{"x":0.017333984375,"y":0.1955413818359375},{"x":0.08465576171875,"y":-0.00628662109375},{"x":0.39434814453125,"y":-0.2357635498046875},{"x":0.30908203125,"y":-0.1047821044921875},{"x":-0.10211181640625,"y":0.3470001220703125},{"x":-0.031005859375,"y":9.918212890625E-4},{"x":0.0845947265625,"y":0.164031982421875},{"x":0.26812744140625,"y":0.246490478515625}],"optimisedCameraToObject":{"translation":{"x":0.17138264525875638,"y":-0.2813007452027751,"z":0.7539567728267917},"rotation":{"quaternion":{"W":0.9827523221429988,"X":0.09195102006070209,"Y":0.15738290927159682,"Z":0.031201011226373154}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":54.021060943603516,"y":345.8491516113281},{"x":80.6604232788086,"y":347.9986877441406},{"x":107.37610626220703,"y":350.2543029785156},{"x":134.38453674316406,"y":352.951171875},{"x":161.2216339111328,"y":355.3465270996094},{"x":188.6256103515625,"y":357.83685302734375},{"x":215.398681640625,"y":360.0675048828125},{"x":52.778690338134766,"y":373.049072265625},{"x":79.32679748535156,"y":375.1228942871094},{"x":105.89820098876953,"y":377.8143005371094},{"x":132.64906311035156,"y":380.1212158203125},{"x":159.46510314941406,"y":382.7596130371094},{"x":186.77223205566406,"y":385.237060546875},{"x":213.88624572753906,"y":387.6988830566406},{"x":51.31965255737305,"y":400.0137939453125},{"x":77.89776611328125,"y":402.0867004394531},{"x":104.51695251464844,"y":404.90045166015625},{"x":131.23776245117188,"y":407.3962707519531},{"x":157.92202758789062,"y":409.95086669921875},{"x":184.858642578125,"y":412.3852233886719},{"x":211.6796875,"y":415.0224914550781},{"x":50.216064453125,"y":426.903564453125},{"x":76.48403930664062,"y":429.3251953125},{"x":102.92842864990234,"y":431.9815979003906},{"x":129.36061096191406,"y":434.6663818359375},{"x":156.23484802246094,"y":437.089111328125},{"x":183.0674591064453,"y":439.8330078125},{"x":209.96823120117188,"y":442.1966857910156},{"x":49.0931282043457,"y":453.1805725097656},{"x":75.02845001220703,"y":455.94610595703125},{"x":101.50030517578125,"y":458.5848388671875},{"x":127.96678161621094,"y":461.2262878417969},{"x":154.43560791015625,"y":463.8559265136719},{"x":181.41050720214844,"y":466.3123474121094},{"x":208.05648803710938,"y":469.11468505859375},{"x":47.83256912231445,"y":479.9390869140625},{"x":72.99527740478516,"y":482.4075012207031},{"x":99.99420166015625,"y":485.33514404296875},{"x":126.40711975097656,"y":488.1174621582031},{"x":152.93824768066406,"y":490.9019470214844},{"x":179.83306884765625,"y":493.5959167480469},{"x":206.09521484375,"y":496.2043151855469},{"x":46.79403305053711,"y":506.0128479003906},{"x":72.34687042236328,"y":508.8729553222656},{"x":98.41320037841797,"y":511.9922180175781},{"x":124.83399200439453,"y":514.6483154296875},{"x":151.21229553222656,"y":517.3984375},{"x":177.8666534423828,"y":520.215087890625},{"x":204.25149536132812,"y":523.1304931640625}],"reprojectionErrors":[{"x":0.15678024291992188,"y":-0.183197021484375},{"x":0.02092742919921875,"y":0.0977783203125},{"x":-0.04419708251953125,"y":0.278961181640625},{"x":-0.2590179443359375,"y":0.02471923828125},{"x":-0.163543701171875,"y":0.077392578125},{"x":-0.5001983642578125,"y":0.040130615234375},{"x":-0.0754241943359375,"y":0.26708984375},{"x":0.010646820068359375,"y":-0.253173828125},{"x":-0.10228729248046875,"y":0.161956787109375},{"x":-0.09206390380859375,"y":-0.03564453125},{"x":-0.1188201904296875,"y":0.1556396484375},{"x":-0.072357177734375,"y":0.01934814453125},{"x":-0.38275146484375,"y":0.04754638671875},{"x":-0.370025634765625,"y":0.0943603515625},{"x":0.09525299072265625,"y":-0.223052978515625},{"x":-0.1161651611328125,"y":0.250823974609375},{"x":-0.2227935791015625,"y":-0.01275634765625},{"x":-0.2891387939453125,"y":0.0445556640625},{"x":-0.18109130859375,"y":0.0455322265625},{"x":-0.1916961669921875,"y":0.16876220703125},{"x":0.0427398681640625,"y":0.09063720703125},{"x":-0.16155242919921875,"y":-0.25360107421875},{"x":-0.131439208984375,"y":-0.0712890625},{"x":-0.1324615478515625,"y":-0.12176513671875},{"x":0.0200347900390625,"y":-0.199127197265625},{"x":-0.1322174072265625,"y":-0.013427734375},{"x":-0.10968017578125,"y":-0.14837646484375},{"x":-0.0263519287109375,"y":0.096954345703125},{"x":-0.3849906921386719,"y":0.1925048828125},{"x":-0.09095001220703125,"y":0.087432861328125},{"x":-0.1887664794921875,"y":0.109710693359375},{"x":-0.14046478271484375,"y":0.12933349609375},{"x":0.042236328125,"y":0.16033935546875},{"x":-0.1485137939453125,"y":0.3636474609375},{"x":0.1180877685546875,"y":0.2196044921875},{"x":-0.456817626953125,"y":0.020477294921875},{"x":0.540985107421875,"y":0.268341064453125},{"x":-0.153350830078125,"y":0.056182861328125},{"x":-0.1215057373046875,"y":-0.01202392578125},{"x":-0.071685791015625,"y":-0.084259033203125},{"x":-0.2534942626953125,"y":-0.068328857421875},{"x":0.3253173828125,"y":0.0302734375},{"x":-0.7367134094238281,"y":0.396087646484375},{"x":-0.19800567626953125,"y":0.307464599609375},{"x":-0.02930450439453125,"y":-0.04254150390625},{"x":-0.075469970703125,"y":0.06793212890625},{"x":0.05645751953125,"y":0.0810546875},{"x":0.04388427734375,"y":0.02386474609375},{"x":0.4282379150390625,"y":-0.136474609375}],"optimisedCameraToObject":{"translation":{"x":-0.3376944754930934,"y":0.010670399215407439,"z":0.6308653198319402},"rotation":{"quaternion":{"W":0.9982657804214611,"X":0.029791771900953612,"Y":0.029229776026813533,"Z":0.04151508352340248}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":169.9084014892578,"y":379.78753662109375},{"x":196.73521423339844,"y":382.94451904296875},{"x":223.49105834960938,"y":386.1179504394531},{"x":250.33724975585938,"y":389.3939208984375},{"x":277.0940246582031,"y":392.5008544921875},{"x":303.8894958496094,"y":395.5666198730469},{"x":330.424072265625,"y":398.856689453125},{"x":167.05535888671875,"y":406.4210205078125},{"x":193.77183532714844,"y":409.4658203125},{"x":220.65167236328125,"y":412.78973388671875},{"x":247.35498046875,"y":416.1004943847656},{"x":273.9166564941406,"y":419.171630859375},{"x":300.79022216796875,"y":422.2829284667969},{"x":327.4206237792969,"y":425.6172180175781},{"x":164.34991455078125,"y":432.7615661621094},{"x":190.96731567382812,"y":435.82049560546875},{"x":217.72662353515625,"y":438.82293701171875},{"x":244.43817138671875,"y":441.98480224609375},{"x":270.94586181640625,"y":445.5509033203125},{"x":297.7475891113281,"y":448.7810974121094},{"x":324.2535400390625,"y":451.9615173339844},{"x":161.87857055664062,"y":459.0615234375},{"x":188.09515380859375,"y":462.1319274902344},{"x":214.9080352783203,"y":465.37811279296875},{"x":241.51596069335938,"y":468.8562316894531},{"x":268.1548156738281,"y":471.958740234375},{"x":294.5619812011719,"y":475.14068603515625},{"x":321.0926513671875,"y":478.1224365234375},{"x":159.09461975097656,"y":485.0336608886719},{"x":185.63937377929688,"y":488.1323547363281},{"x":212.0060272216797,"y":491.2232360839844},{"x":238.78387451171875,"y":494.78778076171875},{"x":265.02703857421875,"y":497.9711608886719},{"x":291.7558898925781,"y":501.07452392578125},{"x":317.98138427734375,"y":504.1951904296875},{"x":156.3255615234375,"y":511.2371826171875},{"x":182.9231719970703,"y":514.3885498046875},{"x":209.1217498779297,"y":517.6865234375},{"x":235.95286560058594,"y":520.790771484375},{"x":262.50238037109375,"y":524.3716430664062},{"x":288.48516845703125,"y":527.1818237304688},{"x":315.14971923828125,"y":530.8562622070312},{"x":153.8773193359375,"y":536.93212890625},{"x":180.115966796875,"y":540.3148193359375},{"x":206.3045196533203,"y":543.87158203125},{"x":232.95066833496094,"y":546.8753662109375},{"x":259.12579345703125,"y":550.2133178710938},{"x":285.5578918457031,"y":553.22021484375},{"x":311.8815612792969,"y":556.64306640625}],"reprojectionErrors":[{"x":0.0184478759765625,"y":-0.13311767578125},{"x":-0.0904693603515625,"y":-0.03399658203125},{"x":-0.10821533203125,"y":0.042572021484375},{"x":-0.2010650634765625,"y":0.009918212890625},{"x":-0.194183349609375,"y":0.13897705078125},{"x":-0.220611572265625,"y":0.30133056640625},{"x":0.014251708984375,"y":0.230865478515625},{"x":0.1129302978515625,"y":-0.2142333984375},{"x":0.058746337890625,"y":-0.004974365234375},{"x":-0.1385040283203125,"y":-0.08258056640625},{"x":-0.143829345703125,"y":-0.15533447265625},{"x":0.002960205078125,"y":0.00262451171875},{"x":-0.156585693359375,"y":0.11090087890625},{"x":-0.0723876953125,"y":-0.013916015625},{"x":0.0755615234375,"y":-0.11480712890625},{"x":0.0645751953125,"y":0.07818603515625},{"x":-0.067901611328125,"y":0.318328857421875},{"x":-0.1371002197265625,"y":0.389129638671875},{"x":0.008209228515625,"y":0.045166015625},{"x":-0.13482666015625,"y":0.0260009765625},{"x":0.01873779296875,"y":0.044921875},{"x":-0.1800994873046875,"y":-0.08795166015625},{"x":0.1535797119140625,"y":0.091339111328125},{"x":-0.0884857177734375,"y":0.083953857421875},{"x":-0.109954833984375,"y":-0.166900634765625},{"x":-0.151580810546875,"y":-0.054229736328125},{"x":0.044403076171875,"y":-0.033721923828125},{"x":0.11785888671875,"y":0.173736572265625},{"x":-0.1072998046875,"y":0.152740478515625},{"x":-0.1581878662109375,"y":0.301483154296875},{"x":-0.01031494140625,"y":0.445526123046875},{"x":-0.25787353515625,"y":0.10284423828125},{"x":0.040191650390625,"y":0.12762451171875},{"x":-0.141357421875,"y":0.2181396484375},{"x":0.181640625,"y":0.276519775390625},{"x":-0.033477783203125,"y":0.04736328125},{"x":-0.193878173828125,"y":0.14105224609375},{"x":0.065521240234375,"y":0.07415771484375},{"x":-0.291717529296875,"y":0.186279296875},{"x":-0.35626220703125,"y":-0.1934814453125},{"x":0.15216064453125,"y":0.181640625},{"x":-0.019805908203125,"y":-0.32391357421875},{"x":-0.2645263671875,"y":0.33514404296875},{"x":-0.1228485107421875,"y":0.19512939453125},{"x":0.08978271484375,"y":-0.13458251953125},{"x":-0.13916015625,"y":0.07244873046875},{"x":0.114166259765625,"y":-0.0714111328125},{"x":0.116912841796875,"y":0.098388671875},{"x":0.22967529296875,"y":-0.16571044921875}],"optimisedCameraToObject":{"translation":{"x":-0.23276045132651585,"y":0.04247056910912708,"z":0.6401151758906024},"rotation":{"quaternion":{"W":0.9978415297651868,"X":0.026492084004514294,"Y":0.002260344468967054,"Z":0.06004449853109906}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":191.27963256835938,"y":216.85125732421875},{"x":218.47052001953125,"y":217.94668579101562},{"x":245.47113037109375,"y":219.14886474609375},{"x":272.6984558105469,"y":220.8357696533203},{"x":299.729248046875,"y":221.94078063964844},{"x":326.26116943359375,"y":223.40304565429688},{"x":352.9256286621094,"y":224.6544189453125},{"x":189.86184692382812,"y":243.27569580078125},{"x":217.16983032226562,"y":244.93350219726562},{"x":244.09861755371094,"y":246.04212951660156},{"x":271.1670227050781,"y":247.20339965820312},{"x":297.96771240234375,"y":248.6288299560547},{"x":324.9637756347656,"y":249.87075805664062},{"x":351.7329406738281,"y":251.30844116210938},{"x":188.1334228515625,"y":270.4233093261719},{"x":215.7362518310547,"y":271.6968994140625},{"x":242.74481201171875,"y":273.0059509277344},{"x":269.8470153808594,"y":274.04656982421875},{"x":296.7548522949219,"y":275.5838317871094},{"x":323.8454895019531,"y":276.5580749511719},{"x":350.08319091796875,"y":278.0265808105469},{"x":186.9500274658203,"y":297.47869873046875},{"x":214.30479431152344,"y":298.7670593261719},{"x":241.24801635742188,"y":300.0479431152344},{"x":268.4455261230469,"y":301.0298156738281},{"x":295.320068359375,"y":302.075439453125},{"x":322.00225830078125,"y":303.5672302246094},{"x":348.958740234375,"y":304.5511169433594},{"x":185.1971435546875,"y":324.2554626464844},{"x":212.70465087890625,"y":325.37811279296875},{"x":239.93789672851562,"y":326.5377502441406},{"x":267.06201171875,"y":327.84759521484375},{"x":294.1334228515625,"y":328.8582458496094},{"x":320.9775085449219,"y":330.0740661621094},{"x":347.8205261230469,"y":331.12750244140625},{"x":183.9181671142578,"y":351.8352966308594},{"x":211.31854248046875,"y":352.7696838378906},{"x":238.3460693359375,"y":353.86358642578125},{"x":265.9459533691406,"y":354.92620849609375},{"x":292.6164245605469,"y":356.06585693359375},{"x":319.7096862792969,"y":357.0189208984375},{"x":346.3279724121094,"y":358.3317565917969},{"x":182.28382873535156,"y":378.80584716796875},{"x":209.72714233398438,"y":379.8011169433594},{"x":236.80055236816406,"y":380.6304931640625},{"x":264.05438232421875,"y":381.9520568847656},{"x":290.985595703125,"y":382.8981018066406},{"x":318.15606689453125,"y":384.01708984375},{"x":344.934814453125,"y":385.1326904296875}],"reprojectionErrors":[{"x":0.091766357421875,"y":-0.204681396484375},{"x":0.002960205078125,"y":0.048980712890625},{"x":0.0292205810546875,"y":0.1986846923828125},{"x":-0.25103759765625,"y":-0.1338348388671875},{"x":-0.419097900390625,"y":0.1177978515625},{"x":-0.1771240234375,"y":0.0141754150390625},{"x":-0.160919189453125,"y":0.123199462890625},{"x":-0.004638671875,"y":0.146148681640625},{"x":-0.1624298095703125,"y":-0.2011260986328125},{"x":-0.01641845703125,"y":0.0020294189453125},{"x":-0.09002685546875,"y":0.1535491943359375},{"x":0.01953125,"y":0.04168701171875},{"x":-0.155364990234375,"y":0.113861083984375},{"x":-0.19683837890625,"y":-0.0094451904296875},{"x":0.2077484130859375,"y":-0.134246826171875},{"x":-0.197113037109375,"y":-0.13616943359375},{"x":-0.0832977294921875,"y":-0.173828125},{"x":-0.143310546875,"y":0.056427001953125},{"x":-0.09375,"y":-0.210662841796875},{"x":-0.3162841796875,"y":0.084320068359375},{"x":0.22039794921875,"y":-0.11614990234375},{"x":-0.1266326904296875,"y":-0.231536865234375},{"x":-0.23602294921875,"y":-0.287384033203125},{"x":-0.0096282958984375,"y":-0.33758544921875},{"x":-0.117919921875,"y":-0.090789794921875},{"x":0.011749267578125,"y":0.090057373046875},{"x":0.2442626953125,"y":-0.177734375},{"x":0.1085205078125,"y":0.059722900390625},{"x":0.1067962646484375,"y":0.039642333984375},{"x":-0.1082763671875,"y":0.110015869140625},{"x":-0.125030517578125,"y":0.14007568359375},{"x":-0.113250732421875,"y":0.016387939453125},{"x":-0.13397216796875,"y":0.188140869140625},{"x":-0.01708984375,"y":0.150787353515625},{"x":0.006622314453125,"y":0.271697998046875},{"x":-0.135284423828125,"y":-0.403564453125},{"x":-0.196533203125,"y":-0.18463134765625},{"x":0.0389556884765625,"y":-0.130126953125},{"x":-0.378692626953125,"y":-0.0494384765625},{"x":0.047637939453125,"y":-0.051025390625},{"x":-0.03875732421875,"y":0.128509521484375},{"x":0.255340576171875,"y":-0.057373046875},{"x":-0.023529052734375,"y":-0.14984130859375},{"x":-0.0813751220703125,"y":-0.031829833984375},{"x":0.1544036865234375,"y":0.24560546875},{"x":0.128753662109375,"y":0.024200439453125},{"x":0.340118408203125,"y":0.171539306640625},{"x":0.2220458984375,"y":0.13897705078125},{"x":0.4010009765625,"y":0.1026611328125}],"optimisedCameraToObject":{"translation":{"x":-0.2150847523788902,"y":-0.10937536181850693,"z":0.6429841641418208},"rotation":{"quaternion":{"W":0.9993159980263666,"X":-0.020445743598099413,"Y":-0.021328105240713092,"Z":0.02224004460716604}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":59.23370361328125,"y":38.33932113647461},{"x":87.00922393798828,"y":42.854488372802734},{"x":115.02725982666016,"y":47.634586334228516},{"x":143.60504150390625,"y":52.71324157714844},{"x":171.82850646972656,"y":57.26994705200195},{"x":200.09176635742188,"y":62.67976760864258},{"x":228.7822265625,"y":67.39237976074219},{"x":58.10192108154297,"y":68.38838195800781},{"x":85.84864044189453,"y":73.02838897705078},{"x":113.53894805908203,"y":78.06898498535156},{"x":141.32225036621094,"y":82.71914672851562},{"x":169.2020263671875,"y":87.6176528930664},{"x":197.4345703125,"y":92.37641143798828},{"x":225.79214477539062,"y":97.39598846435547},{"x":56.9709358215332,"y":97.74823760986328},{"x":84.2510757446289,"y":102.57099914550781},{"x":111.88727569580078,"y":107.37693786621094},{"x":139.54527282714844,"y":112.22335052490234},{"x":167.1638946533203,"y":117.38727569580078},{"x":195.0981903076172,"y":121.94737243652344},{"x":222.89840698242188,"y":127.00836944580078},{"x":56.05445861816406,"y":126.9969482421875},{"x":83.18038177490234,"y":131.7643280029297},{"x":110.25074768066406,"y":136.32122802734375},{"x":137.76243591308594,"y":141.2616424560547},{"x":165.10943603515625,"y":146.13067626953125},{"x":192.70748901367188,"y":151.25067138671875},{"x":220.0210723876953,"y":155.9210968017578},{"x":55.16352462768555,"y":154.84536743164062},{"x":81.90992736816406,"y":159.82772827148438},{"x":107.75545501708984,"y":164.19235229492188},{"x":136.01239013671875,"y":169.29620361328125},{"x":162.9975128173828,"y":174.12254333496094},{"x":190.13108825683594,"y":179.03558349609375},{"x":217.07798767089844,"y":183.92031860351562},{"x":54.216739654541016,"y":182.7169189453125},{"x":80.44190216064453,"y":187.70164489746094},{"x":107.44196319580078,"y":192.23924255371094},{"x":134.1920166015625,"y":197.17784118652344},{"x":160.91378784179688,"y":202.044921875},{"x":187.84996032714844,"y":206.74261474609375},{"x":214.6104278564453,"y":211.8448486328125},{"x":53.25253677368164,"y":209.8740692138672},{"x":79.40377044677734,"y":214.40386962890625},{"x":105.58558654785156,"y":219.63250732421875},{"x":132.1798858642578,"y":224.1912841796875},{"x":158.90245056152344,"y":228.87069702148438},{"x":185.24468994140625,"y":233.74179077148438},{"x":211.927001953125,"y":238.5734405517578}],"reprojectionErrors":[{"x":-0.317718505859375,"y":-0.3343505859375},{"x":-0.0537567138671875,"y":-0.004772186279296875},{"x":0.0700836181640625,"y":0.0789031982421875},{"x":-0.2684173583984375,"y":-0.1178131103515625},{"x":-0.1602630615234375,"y":0.22472000122070312},{"x":-0.00469970703125,"y":-0.26944732666015625},{"x":-0.1942901611328125,"y":-0.05088043212890625},{"x":-0.23468017578125,"y":-0.15471649169921875},{"x":-0.252471923828125,"y":0.039794921875},{"x":-0.1133575439453125,"y":-0.1494140625},{"x":0.028350830078125,"y":0.0678253173828125},{"x":0.1642303466796875,"y":0.0518798828125},{"x":0.032958984375,"y":0.18994903564453125},{"x":-0.14276123046875,"y":0.08058929443359375},{"x":-0.1221466064453125,"y":0.05649566650390625},{"x":0.0223846435546875,"y":0.057220458984375},{"x":-0.09051513671875,"y":0.08957672119140625},{"x":-0.131378173828125,"y":0.09540557861328125},{"x":-0.043853759765625,"y":-0.20318603515625},{"x":-0.18792724609375,"y":0.1142730712890625},{"x":-0.1187896728515625,"y":-0.05783843994140625},{"x":-0.19474411010742188,"y":-0.25917816162109375},{"x":-0.19415283203125,"y":-0.21484375},{"x":-0.0411834716796875,"y":0.05279541015625},{"x":-0.237396240234375,"y":-0.051116943359375},{"x":-0.1815338134765625,"y":-0.0725250244140625},{"x":-0.29412841796875,"y":-0.3346710205078125},{"x":-0.044525146484375,"y":-0.1378631591796875},{"x":-0.2644004821777344,"y":0.206268310546875},{"x":-0.1765289306640625,"y":0.023162841796875},{"x":0.9072952270507812,"y":0.4687042236328125},{"x":-0.3298187255859375,"y":0.1850738525390625},{"x":-0.2092742919921875,"y":0.18817138671875},{"x":-0.1560516357421875,"y":0.1129150390625},{"x":0.16021728515625,"y":0.073455810546875},{"x":-0.2505683898925781,"y":0.0474853515625},{"x":0.072052001953125,"y":-0.151092529296875},{"x":-0.28685760498046875,"y":0.106536865234375},{"x":-0.306884765625,"y":-0.0286102294921875},{"x":-0.2143096923828125,"y":-0.0848541259765625},{"x":-0.2564239501953125,"y":0.0348358154296875},{"x":-0.0477752685546875,"y":-0.244354248046875},{"x":-0.19250106811523438,"y":0.0194549560546875},{"x":-0.0768585205078125,"y":0.2621002197265625},{"x":0.09990692138671875,"y":-0.186798095703125},{"x":-0.0485076904296875,"y":0.0406494140625},{"x":-0.242340087890625,"y":0.153106689453125},{"x":0.0225067138671875,"y":0.0786590576171875},{"x":0.02105712890625,"y":0.0475921630859375}],"optimisedCameraToObject":{"translation":{"x":-0.31398098365329796,"y":-0.26199779844573945,"z":0.5907639670993632},"rotation":{"quaternion":{"W":0.9872467645719031,"X":0.1304301838620576,"Y":0.02714312407484395,"Z":0.0871495484525126}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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.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.72689819335938,"y":33.15799331665039},{"x":263.7967529296875,"y":40.7578010559082},{"x":287.8833312988281,"y":48.0333251953125},{"x":311.61834716796875,"y":55.17482376098633},{"x":334.3671875,"y":62.214752197265625},{"x":357.2959289550781,"y":69.20870971679688},{"x":379.2075500488281,"y":75.70208740234375},{"x":234.3531494140625,"y":58.178619384765625},{"x":258.6037292480469,"y":65.50260925292969},{"x":282.2972106933594,"y":72.17964935302734},{"x":305.9635009765625,"y":79.34990692138672},{"x":328.97607421875,"y":86.25747680664062},{"x":351.84820556640625,"y":92.91856384277344},{"x":373.8199462890625,"y":99.42518615722656},{"x":253.5649871826172,"y":89.9132080078125},{"x":276.9542236328125,"y":96.32315826416016},{"x":300.2864990234375,"y":103.17231750488281},{"x":323.1972351074219,"y":109.72388458251953},{"x":345.8652648925781,"y":116.2955322265625},{"x":367.6835632324219,"y":122.4262924194336},{"x":248.2954559326172,"y":113.93680572509766},{"x":271.8513488769531,"y":120.30672454833984},{"x":294.8355712890625,"y":126.57392120361328},{"x":318.0011901855469,"y":133.02987670898438},{"x":340.1617126464844,"y":139.28271484375},{"x":362.13580322265625,"y":145.26304626464844},{"x":219.8536376953125,"y":130.91848754882812},{"x":243.47097778320312,"y":137.08999633789062},{"x":266.92474365234375,"y":143.48121643066406},{"x":289.93817138671875,"y":149.64295959472656},{"x":312.24273681640625,"y":155.601806640625},{"x":334.6473388671875,"y":161.81057739257812},{"x":356.7762756347656,"y":167.82608032226562},{"x":214.8106689453125,"y":154.2523956298828},{"x":238.4207000732422,"y":160.69053649902344},{"x":261.7353210449219,"y":166.7123565673828},{"x":284.6801452636719,"y":172.58462524414062},{"x":307.0385437011719,"y":178.3723907470703},{"x":329.4573974609375,"y":184.3551788330078},{"x":351.25018310546875,"y":190.03836059570312},{"x":210.06382751464844,"y":177.6529998779297},{"x":233.64175415039062,"y":183.278076171875},{"x":256.6298522949219,"y":189.24708557128906},{"x":279.5111083984375,"y":194.890625},{"x":302.297607421875,"y":200.62628173828125},{"x":324.1338195800781,"y":206.17138671875},{"x":345.5912170410156,"y":211.9669189453125}],"reprojectionErrors":[{"x":0.086334228515625,"y":0.33527374267578125},{"x":0.296661376953125,"y":0.07115936279296875},{"x":0.092559814453125,"y":0.015522003173828125},{"x":-0.151641845703125,"y":-0.020183563232421875},{"x":0.204559326171875,"y":-0.06673049926757812},{"x":9.765625E-4,"y":-0.17804718017578125},{"x":0.440399169921875,"y":0.10211944580078125},{"x":0.2983856201171875,"y":0.2153472900390625},{"x":0.19818115234375,"y":-0.02845001220703125},{"x":0.2625732421875,"y":0.26258087158203125},{"x":-0.032501220703125,"y":-0.05007171630859375},{"x":-0.054718017578125,"y":-0.2088775634765625},{"x":-0.3116455078125,"y":-0.2284393310546875},{"x":-0.037689208984375,"y":-0.199188232421875},{"x":0.020050048828125,"y":-0.14000701904296875},{"x":0.26483154296875,"y":0.172515869140625},{"x":0.18487548828125,"y":-0.0611419677734375},{"x":0.150390625,"y":-0.1026153564453125},{"x":-0.011871337890625,"y":-0.26802825927734375},{"x":0.3106689453125,"y":-0.094879150390625},{"x":0.146026611328125,"y":-0.20459747314453125},{"x":0.101043701171875,"y":-0.0915985107421875},{"x":0.25091552734375,"y":0.02051544189453125},{"x":-0.151947021484375,"y":-0.1582183837890625},{"x":0.084442138671875,"y":-0.23443603515625},{"x":0.146759033203125,"y":-0.13726806640625},{"x":-0.249755859375,"y":0.087615966796875},{"x":-0.101043701171875,"y":0.267181396484375},{"x":-0.166229248046875,"y":0.1251983642578125},{"x":-0.163116455078125,"y":0.1123504638671875},{"x":0.182220458984375,"y":0.2034912109375},{"x":0.066162109375,"y":-0.0527496337890625},{"x":-0.130279541015625,"y":-0.2117462158203125},{"x":-0.081146240234375,"y":0.281585693359375},{"x":-0.0515594482421875,"y":-0.0366058349609375},{"x":-0.09918212890625,"y":-0.037139892578125},{"x":-0.144317626953125,"y":0.0146636962890625},{"x":0.034942626953125,"y":0.0551605224609375},{"x":-0.203155517578125,"y":-0.1938018798828125},{"x":-0.16693115234375,"y":-0.2361907958984375},{"x":-0.1399993896484375,"y":0.0806732177734375},{"x":-0.2039031982421875,"y":0.35009765625},{"x":-0.045806884765625,"y":0.180023193359375},{"x":-0.143524169921875,"y":0.2411956787109375},{"x":-0.5040283203125,"y":0.1174163818359375},{"x":-0.2667236328125,"y":0.092681884765625},{"x":0.001922607421875,"y":-0.2726593017578125}],"optimisedCameraToObject":{"translation":{"x":-0.1772052793529076,"y":-0.31064962242169675,"z":0.6964298094590401},"rotation":{"quaternion":{"W":0.980487576646583,"X":0.11542997233129565,"Y":-0.10535054120298924,"Z":0.11925307961450929}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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":629.2418823242188,"y":394.1077880859375},{"x":652.1565551757812,"y":395.2142028808594},{"x":674.8081665039062,"y":396.2560119628906},{"x":696.96484375,"y":397.7439880371094},{"x":719.1268310546875,"y":398.5635681152344},{"x":741.2089233398438,"y":399.87408447265625},{"x":626.5735473632812,"y":417.6573791503906},{"x":649.3732299804688,"y":418.90576171875},{"x":671.9674072265625,"y":419.70977783203125},{"x":694.2720947265625,"y":420.81756591796875},{"x":717.0031127929688,"y":421.7893371582031},{"x":738.462158203125,"y":422.5842590332031},{"x":759.8959350585938,"y":423.5893249511719},{"x":623.9418334960938,"y":440.7262268066406},{"x":646.517333984375,"y":441.8302001953125},{"x":669.081298828125,"y":442.8855285644531},{"x":691.0248413085938,"y":443.8077087402344},{"x":713.1117553710938,"y":444.478759765625},{"x":735.1264038085938,"y":445.4458312988281},{"x":756.6378173828125,"y":446.18804931640625},{"x":620.8837890625,"y":464.0538635253906},{"x":643.678466796875,"y":465.0412902832031},{"x":666.0115966796875,"y":465.7765808105469},{"x":688.1702880859375,"y":466.5329284667969},{"x":710.4564819335938,"y":467.65313720703125},{"x":732.0682983398438,"y":468.0877685546875},{"x":753.5613403320312,"y":468.8585510253906},{"x":618.0928344726562,"y":486.66046142578125},{"x":641.1178588867188,"y":486.632568359375},{"x":663.0654907226562,"y":488.0837707519531},{"x":685.4207763671875,"y":489.043212890625},{"x":707.2129516601562,"y":489.89117431640625},{"x":727.479248046875,"y":488.995361328125},{"x":750.6743774414062,"y":491.03582763671875},{"x":615.8975830078125,"y":509.5317687988281},{"x":637.9851684570312,"y":510.2052917480469},{"x":660.0061645507812,"y":510.9342346191406},{"x":682.269287109375,"y":511.4956970214844},{"x":704.420654296875,"y":512.0977783203125},{"x":726.2296752929688,"y":512.9381103515625},{"x":747.3182373046875,"y":512.0670166015625},{"x":613.0365600585938,"y":531.901611328125},{"x":635.4527587890625,"y":532.40478515625},{"x":657.7189331054688,"y":533.3848266601562},{"x":680.1582641601562,"y":533.1809692382812},{"x":701.40185546875,"y":534.449462890625},{"x":723.0699462890625,"y":535.0682983398438},{"x":744.3041381835938,"y":535.392333984375}],"reprojectionErrors":[{"x":0.18115234375,"y":0.1744384765625},{"x":0.07818603515625,"y":0.20147705078125},{"x":0.03546142578125,"y":0.274505615234375},{"x":0.2835693359375,"y":-0.1171875},{"x":0.3212890625,"y":0.1409912109375},{"x":0.2327880859375,"y":-0.110260009765625},{"x":0.10357666015625,"y":0.057861328125},{"x":0.03619384765625,"y":-0.155853271484375},{"x":-0.0269775390625,"y":0.0557861328125},{"x":-0.0030517578125,"y":-0.055267333984375},{"x":-0.6090087890625,"y":-0.0491943359375},{"x":-0.1474609375,"y":0.114959716796875},{"x":0.13385009765625,"y":0.05029296875},{"x":0.006103515625,"y":0.2325439453125},{"x":0.08367919921875,"y":0.065948486328125},{"x":-0.02691650390625,"y":-0.071380615234375},{"x":0.2821044921875,"y":-0.0948486328125},{"x":0.24578857421875,"y":0.11358642578125},{"x":0.0787353515625,"y":0.006927490234375},{"x":0.21112060546875,"y":0.106109619140625},{"x":0.3516845703125,"y":-0.039947509765625},{"x":0.1309814453125,"y":-0.185760498046875},{"x":0.17376708984375,"y":-0.099212646484375},{"x":0.1917724609375,"y":-0.053375244140625},{"x":-0.1181640625,"y":-0.39093017578125},{"x":0.04486083984375,"y":-0.062347412109375},{"x":0.1243896484375,"y":-0.089202880859375},{"x":0.44671630859375,"y":0.221343994140625},{"x":-0.0831298828125,"y":0.996551513671875},{"x":0.26788330078125,"y":0.27252197265625},{"x":0.01348876953125,"y":0.020263671875},{"x":0.1234130859375,"y":-0.140411376953125},{"x":1.55938720703125,"y":1.422943115234375},{"x":-0.13427734375,"y":0.0303955078125},{"x":-0.03741455078125,"y":0.031707763671875},{"x":0.29156494140625,"y":0.0126953125},{"x":0.4920654296875,"y":-0.082244873046875},{"x":0.25433349609375,"y":-0.03009033203125},{"x":-0.0689697265625,"y":-0.03875732421875},{"x":-0.2481689453125,"y":-0.3057861328125},{"x":0.09381103515625,"y":1.1187744140625},{"x":0.16070556640625,"y":0.15850830078125},{"x":0.08258056640625,"y":0.218505859375},{"x":-0.0389404296875,"y":-0.21929931640625},{"x":-0.5283203125,"y":0.506103515625},{"x":-0.01763916015625,"y":-0.26141357421875},{"x":-0.1282958984375,"y":-0.399658203125},{"x":-0.002685546875,"y":-0.2633056640625}],"optimisedCameraToObject":{"translation":{"x":0.22587121444809832,"y":0.06782473654955659,"z":0.7122782957843503},"rotation":{"quaternion":{"W":0.9960185650340947,"X":0.059174624276497376,"Y":-0.057065697846571985,"Z":0.03448025635696428}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":448.01922607421875,"y":429.3711242675781},{"x":472.0490417480469,"y":429.4726867675781},{"x":496.2168884277344,"y":429.271728515625},{"x":520.0890502929688,"y":429.09942626953125},{"x":543.7279663085938,"y":428.93798828125},{"x":566.9014892578125,"y":428.8719787597656},{"x":589.7700805664062,"y":428.5798034667969},{"x":446.55126953125,"y":454.0658264160156},{"x":470.9622497558594,"y":453.92071533203125},{"x":495.0009460449219,"y":453.31109619140625},{"x":519.0226440429688,"y":453.2720947265625},{"x":541.9225463867188,"y":453.7502136230469},{"x":565.2225341796875,"y":452.8781433105469},{"x":588.140380859375,"y":452.4361877441406},{"x":445.11834716796875,"y":478.656982421875},{"x":469.5306701660156,"y":477.9880676269531},{"x":493.20819091796875,"y":477.6735534667969},{"x":517.0267333984375,"y":477.4759216308594},{"x":540.4405517578125,"y":476.9804992675781},{"x":563.9301147460938,"y":476.72149658203125},{"x":586.2576904296875,"y":476.05255126953125},{"x":443.876220703125,"y":502.9913635253906},{"x":468.0343322753906,"y":502.4150390625},{"x":491.8365783691406,"y":501.8389587402344},{"x":515.945556640625,"y":501.2271728515625},{"x":539.0038452148438,"y":500.801025390625},{"x":562.118896484375,"y":500.0229797363281},{"x":584.1614990234375,"y":499.4252624511719},{"x":442.5850524902344,"y":526.896728515625},{"x":466.790283203125,"y":526.1390380859375},{"x":490.6747741699219,"y":525.6089477539062},{"x":514.0472412109375,"y":524.7410888671875},{"x":537.3267211914062,"y":523.8837890625},{"x":560.3927612304688,"y":523.137451171875},{"x":583.093017578125,"y":522.6951293945312},{"x":441.0116271972656,"y":550.9126586914062},{"x":465.08135986328125,"y":550.305908203125},{"x":488.9184265136719,"y":549.2070922851562},{"x":512.8445434570312,"y":548.2455444335938},{"x":535.8231811523438,"y":547.6776123046875},{"x":558.9379272460938,"y":546.9464111328125},{"x":581.3497314453125,"y":546.1129150390625},{"x":439.9410095214844,"y":574.75},{"x":463.8714599609375,"y":573.8395385742188},{"x":487.9673767089844,"y":572.8681030273438},{"x":511.12615966796875,"y":571.3697509765625},{"x":534.253662109375,"y":570.9132690429688},{"x":557.1595458984375,"y":570.0716552734375},{"x":579.8931274414062,"y":568.8884887695312}],"reprojectionErrors":[{"x":-0.24639892578125,"y":0.1151123046875},{"x":0.19097900390625,"y":-0.08154296875},{"x":0.179473876953125,"y":0.014434814453125},{"x":0.1544189453125,"y":0.072052001953125},{"x":0.05517578125,"y":0.10931396484375},{"x":0.11566162109375,"y":0.041839599609375},{"x":0.17724609375,"y":0.191375732421875},{"x":-0.066864013671875,"y":0.092620849609375},{"x":-0.09051513671875,"y":-0.007965087890625},{"x":-0.050567626953125,"y":0.346588134765625},{"x":-0.3006591796875,"y":0.121307373046875},{"x":0.265625,"y":-0.630035400390625},{"x":0.12823486328125,"y":-0.03997802734375},{"x":0.0711669921875,"y":0.111419677734375},{"x":0.084014892578125,"y":-0.007965087890625},{"x":-0.02069091796875,"y":0.266845703125},{"x":0.302825927734375,"y":0.1783447265625},{"x":0.180419921875,"y":-0.03570556640625},{"x":0.159423828125,"y":0.03955078125},{"x":-0.2388916015625,"y":-0.129852294921875},{"x":0.2249755859375,"y":0.102691650390625},{"x":0.05047607421875,"y":-0.03271484375},{"x":0.120361328125,"y":0.003265380859375},{"x":0.24169921875,"y":0.030548095703125},{"x":-0.24652099609375,"y":0.085357666015625},{"x":0.01470947265625,"y":-0.053466796875},{"x":-0.08038330078125,"y":0.151885986328125},{"x":0.5992431640625,"y":0.169403076171875},{"x":0.0723876953125,"y":0.19134521484375},{"x":0.015655517578125,"y":0.26458740234375},{"x":-0.022613525390625,"y":0.10223388671875},{"x":0.15032958984375,"y":0.2698974609375},{"x":0.1171875,"y":0.41949462890625},{"x":-6.103515625E-5,"y":0.450927734375},{"x":-0.04730224609375,"y":0.17132568359375},{"x":0.3829345703125,"y":0.12530517578125},{"x":0.38232421875,"y":-0.0943603515625},{"x":0.314208984375,"y":0.17047119140625},{"x":-0.14166259765625,"y":0.290771484375},{"x":0.05291748046875,"y":0.0103759765625},{"x":-0.18414306640625,"y":-0.113525390625},{"x":-0.01202392578125,"y":-0.14166259765625},{"x":0.197052001953125,"y":0.05908203125},{"x":0.2564697265625,"y":0.0032958984375},{"x":-0.14764404296875,"y":0.00128173828125},{"x":0.088775634765625,"y":0.51934814453125},{"x":0.0614013671875,"y":-0.0111083984375},{"x":-0.037841796875,"y":-0.16278076171875},{"x":-0.25653076171875,"y":0.0211181640625}],"optimisedCameraToObject":{"translation":{"x":0.030663983572605177,"y":0.09924212957492183,"z":0.6759971359780811},"rotation":{"quaternion":{"W":0.9950065596447104,"X":0.05085124118088196,"Y":-0.08407436012820498,"Z":0.017538514857137304}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":331.2314758300781,"y":419.66583251953125},{"x":357.44915771484375,"y":419.03802490234375},{"x":382.97711181640625,"y":418.446044921875},{"x":408.5722961425781,"y":417.8908996582031},{"x":433.7213134765625,"y":417.1686096191406},{"x":458.3932189941406,"y":416.58123779296875},{"x":482.699951171875,"y":416.211181640625},{"x":331.2535705566406,"y":445.0315246582031},{"x":357.1666259765625,"y":444.2899475097656},{"x":382.68768310546875,"y":443.8746337890625},{"x":408.2138366699219,"y":443.0794677734375},{"x":433.305908203125,"y":442.2578430175781},{"x":458.0511169433594,"y":441.69610595703125},{"x":482.2638854980469,"y":440.8596496582031},{"x":330.9165344238281,"y":470.82818603515625},{"x":357.001953125,"y":469.8637390136719},{"x":382.3955078125,"y":468.73876953125},{"x":407.6886901855469,"y":467.8902587890625},{"x":432.600341796875,"y":467.098876953125},{"x":457.3919982910156,"y":466.1658630371094},{"x":481.945068359375,"y":465.5999450683594},{"x":330.75653076171875,"y":496.0782470703125},{"x":356.6919250488281,"y":495.0561828613281},{"x":381.9559326171875,"y":493.8338928222656},{"x":407.1277160644531,"y":493.00262451171875},{"x":432.05670166015625,"y":492.1134033203125},{"x":456.91552734375,"y":491.15362548828125},{"x":480.8920593261719,"y":490.1383361816406},{"x":330.5964660644531,"y":520.7067260742188},{"x":356.08636474609375,"y":519.8082275390625},{"x":381.7460632324219,"y":518.437255859375},{"x":406.74658203125,"y":517.2041625976562},{"x":431.4792785644531,"y":516.4271850585938},{"x":456.0859069824219,"y":515.18310546875},{"x":480.34814453125,"y":514.2687377929688},{"x":330.1820068359375,"y":545.9888305664062},{"x":355.9835205078125,"y":544.7557983398438},{"x":381.1116943359375,"y":543.740234375},{"x":406.239013671875,"y":542.09375},{"x":431.1082763671875,"y":541.139892578125},{"x":455.7934875488281,"y":539.9381103515625},{"x":480.0440979003906,"y":538.8885498046875},{"x":330.0758361816406,"y":570.7327270507812},{"x":355.3753967285156,"y":569.1998291015625},{"x":380.9862060546875,"y":568.2113037109375},{"x":405.8823547363281,"y":566.947021484375},{"x":430.70703125,"y":565.4312133789062},{"x":455.37213134765625,"y":564.1724853515625},{"x":479.3182373046875,"y":562.9898071289062}],"reprojectionErrors":[{"x":0.15289306640625,"y":-0.160919189453125},{"x":-0.0601806640625,"y":-0.075469970703125},{"x":0.125518798828125,"y":-0.029754638671875},{"x":-0.046661376953125,"y":-0.02459716796875},{"x":-0.062835693359375,"y":0.1441650390625},{"x":0.10845947265625,"y":0.174560546875},{"x":0.35589599609375,"y":-0.015625},{"x":-0.074462890625,"y":0.097412109375},{"x":-0.058563232421875,"y":0.157135009765625},{"x":0.06005859375,"y":-0.113250732421875},{"x":-0.1153564453125,"y":-0.00738525390625},{"x":-0.145172119140625,"y":0.1214599609375},{"x":-0.11614990234375,"y":-0.01287841796875},{"x":0.157958984375,"y":0.1243896484375},{"x":0.057861328125,"y":-0.23089599609375},{"x":-0.174285888671875,"y":-0.08612060546875},{"x":-0.00213623046875,"y":0.21539306640625},{"x":-0.016876220703125,"y":0.2369384765625},{"x":0.063079833984375,"y":0.197967529296875},{"x":-0.0233154296875,"y":0.297454833984375},{"x":-0.156890869140625,"y":0.02691650390625},{"x":0.013641357421875,"y":-0.16827392578125},{"x":-0.1441650390625,"y":-0.102020263671875},{"x":0.083526611328125,"y":0.1607666015625},{"x":0.11785888671875,"y":0.029022216796875},{"x":0.109832763671875,"y":-0.048004150390625},{"x":-0.11273193359375,"y":-0.057525634765625},{"x":0.262847900390625,"y":-0.014373779296875},{"x":-0.02996826171875,"y":0.36029052734375},{"x":0.1820068359375,"y":0.1685791015625},{"x":-0.05999755859375,"y":0.44561767578125},{"x":0.073272705078125,"y":0.58135986328125},{"x":0.190826416015625,"y":0.2578125},{"x":0.15142822265625,"y":0.3984375},{"x":0.17388916015625,"y":0.20660400390625},{"x":0.18133544921875,"y":0.0797119140625},{"x":0.0059814453125,"y":0.0897216796875},{"x":0.22149658203125,"y":-0.12139892578125},{"x":0.155609130859375,"y":0.2950439453125},{"x":0.06591796875,"y":0.0157470703125},{"x":-0.12115478515625,"y":-0.01849365234375},{"x":-0.154510498046875,"y":-0.20751953125},{"x":0.08489990234375,"y":0.18182373046875},{"x":0.335784912109375,"y":0.36053466796875},{"x":-0.00537109375,"y":-0.0086669921875},{"x":0.087554931640625,"y":-0.10552978515625},{"x":-0.02825927734375,"y":0.046142578125},{"x":-0.264312744140625,"y":-0.06207275390625},{"x":-0.06060791015625,"y":-0.248779296875}],"optimisedCameraToObject":{"translation":{"x":-0.08510351053733864,"y":0.08638864545568846,"z":0.657007128678282},"rotation":{"quaternion":{"W":0.9964491993428661,"X":0.03979958203965251,"Y":-0.07405138753240255,"Z":0.004623678509147961}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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":79.41705322265625,"y":412.6457824707031},{"x":108.00381469726562,"y":411.3244323730469},{"x":136.05938720703125,"y":410.4716796875},{"x":164.1924285888672,"y":409.08343505859375},{"x":191.88783264160156,"y":408.0768737792969},{"x":219.79296875,"y":406.983154296875},{"x":245.4607391357422,"y":405.9814758300781},{"x":80.18347930908203,"y":439.5212707519531},{"x":108.6060562133789,"y":438.123291015625},{"x":136.9456787109375,"y":437.0024108886719},{"x":164.80026245117188,"y":435.5784912109375},{"x":192.12167358398438,"y":434.45269775390625},{"x":219.65176391601562,"y":432.85791015625},{"x":245.95993041992188,"y":431.7634582519531},{"x":80.98406219482422,"y":466.06695556640625},{"x":109.29608154296875,"y":464.751220703125},{"x":137.56219482421875,"y":462.9157409667969},{"x":165.4318389892578,"y":461.8831787109375},{"x":192.87132263183594,"y":460.0674743652344},{"x":219.9458465576172,"y":458.8800354003906},{"x":246.24179077148438,"y":457.25238037109375},{"x":81.7502670288086,"y":492.8155517578125},{"x":110.0806884765625,"y":490.96685791015625},{"x":138.06175231933594,"y":489.39642333984375},{"x":165.8417205810547,"y":488.01123046875},{"x":193.27330017089844,"y":486.28662109375},{"x":220.19271850585938,"y":484.9385070800781},{"x":246.88641357421875,"y":483.18231201171875},{"x":82.42625427246094,"y":518.9642333984375},{"x":110.8089599609375,"y":517.2395629882812},{"x":138.79881286621094,"y":515.4427490234375},{"x":166.10366821289062,"y":513.7586669921875},{"x":193.71697998046875,"y":511.91571044921875},{"x":220.83261108398438,"y":510.2893371582031},{"x":247.11602783203125,"y":508.40679931640625},{"x":83.30671691894531,"y":545.2686767578125},{"x":111.49689483642578,"y":543.816650390625},{"x":139.21246337890625,"y":541.5189208984375},{"x":166.98338317871094,"y":539.8679809570312},{"x":194.01492309570312,"y":537.9791259765625},{"x":221.09169006347656,"y":536.0531616210938},{"x":247.81048583984375,"y":534.2291259765625},{"x":84.15645599365234,"y":571.4194946289062},{"x":112.11708068847656,"y":569.4663696289062},{"x":139.80406188964844,"y":567.9172973632812},{"x":167.52000427246094,"y":565.4815063476562},{"x":194.43228149414062,"y":563.7354736328125},{"x":221.26251220703125,"y":561.8145751953125},{"x":247.91995239257812,"y":559.7775268554688}],"reprojectionErrors":[{"x":-0.02587127685546875,"y":-0.229095458984375},{"x":0.01496124267578125,"y":0.031951904296875},{"x":0.21697998046875,"y":-0.170013427734375},{"x":-0.026214599609375,"y":0.16925048828125},{"x":-0.1971435546875,"y":0.132568359375},{"x":-0.940765380859375,"y":0.188934326171875},{"x":0.1924896240234375,"y":0.15911865234375},{"x":-0.059173583984375,"y":-0.248931884765625},{"x":0.08567047119140625,"y":-0.087554931640625},{"x":-0.0550689697265625,"y":-0.1968994140625},{"x":-0.077056884765625,"y":0.00323486328125},{"x":0.0701751708984375,"y":-0.088226318359375},{"x":-0.35284423828125,"y":0.2958984375},{"x":0.0869598388671875,"y":0.1864013671875},{"x":-0.125885009765625,"y":-0.046875},{"x":0.06905364990234375,"y":-0.142547607421875},{"x":-0.0571746826171875,"y":0.28857421875},{"x":-0.151763916015625,"y":-0.0760498046875},{"x":-0.1787261962890625,"y":0.3497314453125},{"x":-0.200897216796875,"y":0.15460205078125},{"x":0.197784423828125,"y":0.40716552734375},{"x":-0.15750885009765625,"y":-0.15643310546875},{"x":-0.0417327880859375,"y":0.107452392578125},{"x":0.0578155517578125,"y":0.100799560546875},{"x":-0.00494384765625,"y":-0.08319091796875},{"x":-0.0803985595703125,"y":0.0802001953125},{"x":-0.0024566650390625,"y":-0.124786376953125},{"x":-0.0551300048828125,"y":0.086517333984375},{"x":-0.09824371337890625,"y":0.224365234375},{"x":-0.09580230712890625,"y":0.1922607421875},{"x":-0.0646209716796875,"y":0.24066162109375},{"x":0.2896270751953125,"y":0.18499755859375},{"x":-0.02423095703125,"y":0.29681396484375},{"x":-0.19775390625,"y":0.200927734375},{"x":0.1059722900390625,"y":0.370147705078125},{"x":-0.242828369140625,"y":0.3389892578125},{"x":-0.10919189453125,"y":-0.13629150390625},{"x":0.1364288330078125,"y":0.24322509765625},{"x":-0.0337677001953125,"y":-0.01483154296875},{"x":0.17718505859375,"y":-0.02557373046875},{"x":-0.01300048828125,"y":0.01031494140625},{"x":-0.1987762451171875,"y":-0.0460205078125},{"x":-0.35611724853515625,"y":0.49609375},{"x":-0.05454254150390625,"y":0.35284423828125},{"x":0.1595458984375,"y":-0.18475341796875},{"x":-0.0143280029296875,"y":0.17425537109375},{"x":0.258697509765625,"y":-0.14642333984375},{"x":0.259246826171875,"y":-0.281982421875},{"x":0.0804443359375,"y":-0.291015625}],"optimisedCameraToObject":{"translation":{"x":-0.3193690600708015,"y":0.07589749250509525,"z":0.6321032365491306},"rotation":{"quaternion":{"W":0.9959781663685361,"X":0.024649193271525288,"Y":-0.08603038983297161,"Z":-0.004322200066939342}}},"includeObservationInCalibration":true,"snapshotName":"img21.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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/src/main/deploy/calibrations/right_arducam_800.json b/src/main/deploy/calibrations/right_arducam_800.json new file mode 100644 index 0000000..ff683ef --- /dev/null +++ b/src/main/deploy/calibrations/right_arducam_800.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[684.9147374097752,0.0,371.8363893896856,0.0,685.7134152700377,296.110092736614,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04790392233818402,-0.06920591524637874,5.609130214525863E-4,-0.0026251195991928416,0.012128815278404434,-0.001844322544723348,0.003242642793096791,-4.287124080661558E-4]},"calobjectWarp":[-2.2391714350727192E-4,-1.4343522746417786E-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":106.26538848876953,"y":172.49778747558594},{"x":144.2373046875,"y":172.0257110595703},{"x":182.9569854736328,"y":172.08314514160156},{"x":222.75421142578125,"y":172.14108276367188},{"x":262.7756652832031,"y":172.13902282714844},{"x":303.4534912109375,"y":171.98460388183594},{"x":344.9132995605469,"y":172.1147918701172},{"x":104.16173553466797,"y":212.675537109375},{"x":142.37274169921875,"y":212.97708129882812},{"x":180.8836669921875,"y":213.0251007080078},{"x":220.64932250976562,"y":213.31332397460938},{"x":260.2254943847656,"y":213.8289794921875},{"x":301.9626159667969,"y":214.12957763671875},{"x":343.1189270019531,"y":214.73419189453125},{"x":102.10662078857422,"y":253.5009765625},{"x":140.19418334960938,"y":253.99575805664062},{"x":178.9600372314453,"y":254.7830352783203},{"x":218.8439483642578,"y":255.23387145996094},{"x":258.98614501953125,"y":255.99261474609375},{"x":299.958984375,"y":256.9174499511719},{"x":341.7056579589844,"y":257.7732849121094},{"x":100.10343170166016,"y":294.64422607421875},{"x":138.45375061035156,"y":295.24176025390625},{"x":177.15769958496094,"y":296.73486328125},{"x":216.8730926513672,"y":297.6573791503906},{"x":257.0032043457031,"y":298.6906433105469},{"x":297.91375732421875,"y":300.07305908203125},{"x":339.839111328125,"y":300.9164123535156},{"x":98.220458984375,"y":335.0008850097656},{"x":136.12722778320312,"y":336.76531982421875},{"x":175.0268096923828,"y":337.96417236328125},{"x":214.8787078857422,"y":339.4961242675781},{"x":255.21551513671875,"y":340.82794189453125},{"x":296.6320495605469,"y":342.3974609375},{"x":338.2372741699219,"y":343.9622497558594},{"x":95.93185424804688,"y":376.76788330078125},{"x":134.11346435546875,"y":378.8056335449219},{"x":172.84718322753906,"y":380.09686279296875},{"x":213.05792236328125,"y":382.2685241699219},{"x":253.26747131347656,"y":383.9275817871094},{"x":294.50567626953125,"y":386.3393249511719},{"x":336.3748779296875,"y":388.2295227050781},{"x":93.95661926269531,"y":418.0646667480469},{"x":132.08657836914062,"y":420.1647033691406},{"x":170.71168518066406,"y":422.6596374511719},{"x":210.9027099609375,"y":424.997314453125},{"x":251.4449462890625,"y":427.0630798339844},{"x":292.5711669921875,"y":429.25482177734375},{"x":334.8700256347656,"y":432.08349609375}],"reprojectionErrors":[{"x":0.175048828125,"y":0.02569580078125},{"x":-0.05059814453125,"y":0.3511810302734375},{"x":-0.2425689697265625,"y":0.157928466796875},{"x":-0.7171630859375,"y":-0.0247344970703125},{"x":-0.607421875,"y":-0.1359100341796875},{"x":-0.331756591796875,"y":-0.0828857421875},{"x":-0.001953125,"y":-0.3022308349609375},{"x":0.10172271728515625,"y":0.139251708984375},{"x":-0.2750244140625,"y":0.0911407470703125},{"x":-0.166015625,"y":0.3118438720703125},{"x":-0.512451171875,"y":0.3080291748046875},{"x":0.143707275390625,"y":0.0928497314453125},{"x":-0.534149169921875,"y":0.1092071533203125},{"x":0.20977783203125,"y":-0.16156005859375},{"x":-0.0120391845703125,"y":-0.1582183837890625},{"x":-0.1788330078125,"y":0.0051116943359375},{"x":-0.2340545654296875,"y":-0.1041259765625},{"x":-0.603729248046875,"y":0.143402099609375},{"x":-0.41412353515625,"y":0.10382080078125},{"x":-0.22357177734375,"y":-0.0806884765625},{"x":0.03887939453125,"y":-0.17449951171875},{"x":-0.16919708251953125,"y":-0.54144287109375},{"x":-0.51373291015625,"y":-0.07159423828125},{"x":-0.41790771484375,"y":-0.47265625},{"x":-0.5256500244140625,"y":-0.278076171875},{"x":-0.226104736328125,"y":-0.16864013671875},{"x":0.129119873046875,"y":-0.38232421875},{"x":0.32000732421875,"y":-0.030426025390625},{"x":-0.43761444091796875,"y":0.089324951171875},{"x":-0.2551116943359375,"y":-0.1939697265625},{"x":-0.267364501953125,"y":0.1177978515625},{"x":-0.4198150634765625,"y":0.12640380859375},{"x":-0.2308349609375,"y":0.365631103515625},{"x":-0.280914306640625,"y":0.39813232421875},{"x":0.335418701171875,"y":0.46685791015625},{"x":-0.29102325439453125,"y":-0.46771240234375},{"x":-0.301422119140625,"y":-0.60614013671875},{"x":-0.0618438720703125,"y":0.036346435546875},{"x":-0.483001708984375,"y":-0.166656494140625},{"x":-0.07232666015625,"y":0.178375244140625},{"x":0.154815673828125,"y":-0.1932373046875},{"x":0.610687255859375,"y":-0.00677490234375},{"x":-0.44799041748046875,"y":-0.33697509765625},{"x":-0.3263702392578125,"y":-0.115142822265625},{"x":0.106170654296875,"y":-0.248809814453125},{"x":-0.206817626953125,"y":-0.185272216796875},{"x":-0.0361328125,"y":0.190765380859375},{"x":0.40008544921875,"y":0.481964111328125},{"x":0.527923583984375,"y":0.177947998046875}],"optimisedCameraToObject":{"translation":{"x":-0.19036749845810794,"y":-0.10333300905607054,"z":0.4344675123429171},"rotation":{"quaternion":{"W":0.9962619626856976,"X":-0.024641408603911168,"Y":0.08137149124855732,"Z":0.015283425651432496}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":295.1114196777344,"y":160.8417510986328},{"x":337.1856994628906,"y":162.0950927734375},{"x":379.71575927734375,"y":163.93040466308594},{"x":422.8009338378906,"y":165.7616424560547},{"x":466.33868408203125,"y":167.17698669433594},{"x":510.4841003417969,"y":168.9625244140625},{"x":555.15966796875,"y":170.68771362304688},{"x":292.63494873046875,"y":203.2911376953125},{"x":334.7442626953125,"y":205.03578186035156},{"x":376.986572265625,"y":206.73216247558594},{"x":420.0962829589844,"y":208.8799285888672},{"x":463.84521484375,"y":210.35694885253906},{"x":507.9684143066406,"y":212.57696533203125},{"x":552.611572265625,"y":214.77685546875},{"x":290.0498962402344,"y":245.7357940673828},{"x":331.9282531738281,"y":247.90228271484375},{"x":374.29705810546875,"y":249.8118438720703},{"x":417.68548583984375,"y":252.00070190429688},{"x":460.9984436035156,"y":254.33306884765625},{"x":505.14019775390625,"y":256.20465087890625},{"x":550.0460815429688,"y":258.7641296386719},{"x":287.3027038574219,"y":288.52728271484375},{"x":329.2394714355469,"y":290.96209716796875},{"x":371.8866882324219,"y":293.0930480957031},{"x":415.1246337890625,"y":295.3936462402344},{"x":458.5348815917969,"y":297.9795837402344},{"x":502.960205078125,"y":300.727294921875},{"x":547.3397827148438,"y":303.03753662109375},{"x":284.571533203125,"y":330.8458557128906},{"x":326.69757080078125,"y":333.2906188964844},{"x":369.0884704589844,"y":336.03375244140625},{"x":412.3104553222656,"y":338.5302734375},{"x":456.02978515625,"y":341.2061462402344},{"x":500.4403076171875,"y":343.9818420410156},{"x":545.0699462890625,"y":347.17205810546875},{"x":281.67559814453125,"y":373.5444641113281},{"x":323.96124267578125,"y":376.7484436035156},{"x":366.3218078613281,"y":379.6494140625},{"x":409.8246154785156,"y":382.625732421875},{"x":453.09356689453125,"y":385.5916442871094},{"x":497.92340087890625,"y":388.9788818359375},{"x":542.902587890625,"y":392.0830078125},{"x":279.04998779296875,"y":416.38616943359375},{"x":321.1944580078125,"y":419.6591796875},{"x":363.9451599121094,"y":422.9556579589844},{"x":407.0330505371094,"y":426.14117431640625},{"x":450.916015625,"y":429.6610412597656},{"x":495.2188415527344,"y":432.9367980957031},{"x":540.317138671875,"y":436.9145202636719}],"reprojectionErrors":[{"x":-0.00714111328125,"y":-0.0254364013671875},{"x":-0.176361083984375,"y":0.2818603515625},{"x":-0.22943115234375,"y":0.04180908203125},{"x":-0.265625,"y":-0.15924072265625},{"x":-0.18280029296875,"y":0.0907440185546875},{"x":-0.13665771484375,"y":0.005950927734375},{"x":-0.05072021484375,"y":0.017120361328125},{"x":-0.209136962890625,"y":-0.190399169921875},{"x":-0.371978759765625,"y":-0.0880279541015625},{"x":-0.09423828125,"y":0.097320556640625},{"x":-0.11029052734375,"y":-0.133819580078125},{"x":-0.19232177734375,"y":0.3408660888671875},{"x":-0.07598876953125,"y":0.1077728271484375},{"x":0.092041015625,"y":-0.0698089599609375},{"x":-0.301361083984375,"y":-0.227386474609375},{"x":-0.194122314453125,"y":-0.258941650390625},{"x":-0.002166748046875,"y":0.0012054443359375},{"x":-0.25469970703125,"y":0.0169677734375},{"x":0.14312744140625,"y":-0.0758056640625},{"x":0.286376953125,"y":0.3272705078125},{"x":0.23883056640625,"y":0.077606201171875},{"x":-0.229827880859375,"y":-0.494720458984375},{"x":-0.144134521484375,"y":-0.5052490234375},{"x":-0.1922607421875,"y":-0.17706298828125},{"x":-0.25445556640625,"y":0.016357421875},{"x":0.08746337890625,"y":-0.040618896484375},{"x":-0.009918212890625,"y":-0.224456787109375},{"x":0.5133056640625,"y":0.064056396484375},{"x":-0.172210693359375,"y":-0.179443359375},{"x":-0.241241455078125,"y":0.090728759765625},{"x":0.0029296875,"y":0.097503662109375},{"x":-0.005889892578125,"y":0.38580322265625},{"x":0.065826416015625,"y":0.52960205078125},{"x":0.023651123046875,"y":0.60833740234375},{"x":0.33868408203125,"y":0.30718994140625},{"x":0.052734375,"y":-0.1414794921875},{"x":-0.1436767578125,"y":-0.338592529296875},{"x":0.1644287109375,"y":-0.197601318359375},{"x":-0.090240478515625,"y":-0.097076416015625},{"x":0.46826171875,"y":0.04864501953125},{"x":0.0445556640625,"y":-0.19232177734375},{"x":0.04931640625,"y":-0.11578369140625},{"x":0.0103759765625,"y":-0.150848388671875},{"x":-0.01495361328125,"y":-0.123870849609375},{"x":-0.0657958984375,"y":-0.085235595703125},{"x":0.12701416015625,"y":0.099334716796875},{"x":0.1053466796875,"y":-0.0157470703125},{"x":0.243896484375,"y":0.147735595703125},{"x":0.1661376953125,"y":-0.356536865234375}],"optimisedCameraToObject":{"translation":{"x":-0.06957634372888649,"y":-0.10766126988800435,"z":0.41314472303589805},"rotation":{"quaternion":{"W":0.998132832074789,"X":-0.011993282902445833,"Y":0.05208579446217053,"Z":0.029564856076558333}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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.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.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.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.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.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":546.9029541015625,"y":173.29464721679688},{"x":587.1555786132812,"y":176.4973907470703},{"x":626.540771484375,"y":179.84950256347656},{"x":665.3187866210938,"y":182.93994140625},{"x":703.0034790039062,"y":186.16519165039062},{"x":740.083984375,"y":189.37118530273438},{"x":544.0834350585938,"y":216.06256103515625},{"x":584.2326049804688,"y":219.05882263183594},{"x":623.7393188476562,"y":221.82118225097656},{"x":662.9039306640625,"y":224.76182556152344},{"x":701.0478515625,"y":227.2815704345703},{"x":738.0416870117188,"y":230.20843505859375},{"x":541.292724609375,"y":258.9649353027344},{"x":581.4884033203125,"y":261.4376525878906},{"x":620.8909301757812,"y":263.8662414550781},{"x":659.696533203125,"y":266.4356689453125},{"x":697.6683349609375,"y":268.79791259765625},{"x":734.946533203125,"y":270.75335693359375},{"x":538.3374633789062,"y":301.8629455566406},{"x":578.865478515625,"y":303.8603820800781},{"x":617.9742431640625,"y":306.03851318359375},{"x":657.1041259765625,"y":307.9775390625},{"x":695.1043090820312,"y":309.9665222167969},{"x":732.3194580078125,"y":312.1132507324219},{"x":535.9127197265625,"y":343.8997497558594},{"x":576.132080078125,"y":345.7571716308594},{"x":615.6600341796875,"y":347.2552795410156},{"x":654.2923583984375,"y":348.9859313964844},{"x":692.2953491210938,"y":350.6110534667969},{"x":729.7289428710938,"y":352.1037292480469},{"x":533.0113525390625,"y":386.6262512207031},{"x":573.33349609375,"y":388.01031494140625},{"x":612.7150268554688,"y":389.2283935546875},{"x":651.3096923828125,"y":390.5599060058594},{"x":689.6156616210938,"y":391.9150695800781},{"x":727.0118408203125,"y":393.04150390625},{"x":763.282470703125,"y":394.29180908203125},{"x":530.3983154296875,"y":428.57647705078125},{"x":570.848388671875,"y":429.5242614746094},{"x":610.520263671875,"y":430.87554931640625},{"x":649.0460205078125,"y":431.7014465332031},{"x":687.0743408203125,"y":432.302001953125},{"x":724.4049072265625,"y":433.2821350097656},{"x":760.821533203125,"y":434.2322998046875}],"reprojectionErrors":[{"x":-0.22552490234375,"y":-0.140106201171875},{"x":-0.12457275390625,"y":-0.030548095703125},{"x":0.087646484375,"y":-0.121612548828125},{"x":0.16094970703125,"y":-0.001739501953125},{"x":0.591552734375,"y":-0.066864013671875},{"x":0.90057373046875,"y":-0.162384033203125},{"x":-0.0203857421875,"y":0.0159454345703125},{"x":0.15283203125,"y":-0.061065673828125},{"x":0.21405029296875,"y":0.048004150390625},{"x":-0.12689208984375,"y":-0.0684967041015625},{"x":-0.18145751953125,"y":0.189178466796875},{"x":0.18994140625,"y":-0.0064544677734375},{"x":0.14764404296875,"y":-0.07928466796875},{"x":0.24102783203125,"y":-0.023834228515625},{"x":0.375,"y":0.031341552734375},{"x":0.3634033203125,"y":-0.098175048828125},{"x":0.45318603515625,"y":-0.0638427734375},{"x":0.5140380859375,"y":0.334564208984375},{"x":0.47247314453125,"y":-0.293792724609375},{"x":0.197998046875,"y":-0.15203857421875},{"x":0.59228515625,"y":-0.23199462890625},{"x":0.224853515625,"y":-0.11334228515625},{"x":0.25653076171875,"y":-0.08453369140625},{"x":0.3525390625,"y":-0.25286865234375},{"x":0.2593994140625,"y":0.22259521484375},{"x":0.256103515625,"y":0.11761474609375},{"x":0.1956787109375,"y":0.334259033203125},{"x":0.29229736328125,"y":0.281219482421875},{"x":0.28955078125,"y":0.297149658203125},{"x":0.13739013671875,"y":0.4095458984375},{"x":0.51617431640625,"y":-0.087677001953125},{"x":0.37042236328125,"y":-0.103729248046875},{"x":0.41900634765625,"y":0.011810302734375},{"x":0.517822265625,"y":-0.0198974609375},{"x":0.1785888671875,"y":-0.108489990234375},{"x":0.03228759765625,"y":-0.00103759765625},{"x":0.3045654296875,"y":-0.049560546875},{"x":0.47821044921875,"y":0.234832763671875},{"x":0.16290283203125,"y":0.2730712890625},{"x":-0.118408203125,"y":-0.123321533203125},{"x":0.011962890625,"y":-0.02484130859375},{"x":-0.08489990234375,"y":0.26898193359375},{"x":-0.19891357421875,"y":0.15386962890625},{"x":-0.10400390625,"y":0.039886474609375}],"optimisedCameraToObject":{"translation":{"x":0.07997110450341513,"y":-0.09948533955668773,"z":0.4018712156828376},"rotation":{"quaternion":{"W":0.9967663473113645,"X":0.013950107168127036,"Y":-0.07440944055227902,"Z":0.02693470872786355}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":367.3553771972656,"y":196.31065368652344},{"x":406.733642578125,"y":199.09153747558594},{"x":445.41302490234375,"y":201.81582641601562},{"x":484.2298278808594,"y":204.0837860107422},{"x":522.7655639648438,"y":206.94158935546875},{"x":561.7227172851562,"y":209.45388793945312},{"x":599.868896484375,"y":212.190185546875},{"x":364.86602783203125,"y":235.81927490234375},{"x":404.01788330078125,"y":238.02395629882812},{"x":442.447509765625,"y":240.83139038085938},{"x":481.269287109375,"y":243.38124084472656},{"x":519.7448120117188,"y":245.7698516845703},{"x":558.3366088867188,"y":248.60983276367188},{"x":596.3278198242188,"y":251.0729522705078},{"x":362.0566101074219,"y":274.480224609375},{"x":400.8203125,"y":276.6954345703125},{"x":439.7102966308594,"y":279.68890380859375},{"x":477.88677978515625,"y":282.0179748535156},{"x":516.2843627929688,"y":284.7793884277344},{"x":555.0471801757812,"y":287.1521911621094},{"x":593.0676879882812,"y":289.4947814941406},{"x":359.68121337890625,"y":313.329345703125},{"x":397.9988098144531,"y":315.92474365234375},{"x":436.7192687988281,"y":318.3492126464844},{"x":474.91241455078125,"y":320.97314453125},{"x":513.3386840820312,"y":323.07379150390625},{"x":551.8514404296875,"y":325.6566162109375},{"x":589.5569458007812,"y":328.0624694824219},{"x":357.099365234375,"y":351.2790832519531},{"x":395.5191955566406,"y":353.6856689453125},{"x":433.7978515625,"y":356.0232849121094},{"x":472.08612060546875,"y":358.4579162597656},{"x":510.1307067871094,"y":361.0721740722656},{"x":548.2631225585938,"y":363.16693115234375},{"x":586.4135131835938,"y":365.7971496582031},{"x":354.61810302734375,"y":389.55511474609375},{"x":392.7988586425781,"y":392.0729064941406},{"x":430.7272644042969,"y":394.2659606933594},{"x":469.0091247558594,"y":396.6268005371094},{"x":507.07208251953125,"y":398.98992919921875},{"x":545.125732421875,"y":401.66082763671875},{"x":583.0658569335938,"y":404.15289306640625},{"x":351.93914794921875,"y":427.1180114746094},{"x":390.093505859375,"y":429.43389892578125},{"x":428.154541015625,"y":431.86944580078125},{"x":466.3114929199219,"y":434.4603271484375},{"x":504.0509338378906,"y":436.7005615234375},{"x":541.9972534179688,"y":438.92193603515625},{"x":579.9525146484375,"y":441.3321228027344}],"reprojectionErrors":[{"x":-0.0064697265625,"y":-0.0879669189453125},{"x":-0.357391357421875,"y":-0.1941375732421875},{"x":-0.092010498046875,"y":-0.2450714111328125},{"x":-0.055908203125,"y":0.1583404541015625},{"x":0.16021728515625,"y":-0.03076171875},{"x":-0.15533447265625,"y":0.1223602294921875},{"x":0.220947265625,"y":0.04754638671875},{"x":-0.1060791015625,"y":-0.343719482421875},{"x":-0.37548828125,"y":0.0782623291015625},{"x":-0.00439453125,"y":-0.106964111328125},{"x":-0.116424560546875,"y":-0.0396728515625},{"x":0.0177001953125,"y":0.1831512451171875},{"x":-0.07366943359375,"y":-0.05169677734375},{"x":0.3175048828125,"y":0.0833892822265625},{"x":0.133819580078125,"y":-0.048797607421875},{"x":0.10675048828125,"y":0.31512451171875},{"x":-0.127532958984375,"y":-0.106719970703125},{"x":0.261627197265625,"y":0.127716064453125},{"x":0.33050537109375,"y":-0.078857421875},{"x":-0.073974609375,"y":0.0938720703125},{"x":0.1468505859375,"y":0.286956787109375},{"x":-0.0406494140625,"y":-0.241729736328125},{"x":0.23162841796875,"y":-0.305023193359375},{"x":0.020965576171875,"y":-0.2078857421875},{"x":0.2484130859375,"y":-0.321319580078125},{"x":0.14459228515625,"y":0.076904296875},{"x":-0.15289306640625,"y":-0.019287109375},{"x":0.240966796875,"y":0.04876708984375},{"x":0.0111083984375,"y":0.162506103515625},{"x":0.033538818359375,"y":0.24151611328125},{"x":0.117889404296875,"y":0.37603759765625},{"x":0.10430908203125,"y":0.3995361328125},{"x":0.2371826171875,"y":0.228851318359375},{"x":0.1761474609375,"y":0.56256103515625},{"x":-0.01776123046875,"y":0.345184326171875},{"x":-0.017730712890625,"y":-0.064208984375},{"x":0.095306396484375,"y":-0.14239501953125},{"x":0.382232666015625,"y":0.087799072265625},{"x":0.228302001953125,"y":0.133331298828125},{"x":0.196990966796875,"y":0.15911865234375},{"x":0.06988525390625,"y":-0.140777587890625},{"x":-0.05743408203125,"y":-0.2802734375},{"x":0.171234130859375,"y":0.115264892578125},{"x":0.161376953125,"y":0.19354248046875},{"x":0.167205810546875,"y":0.1329345703125},{"x":-0.0093994140625,"y":-0.102752685546875},{"x":0.13616943359375,"y":-0.008026123046875},{"x":-0.0291748046875,"y":0.0848388671875},{"x":-0.316162109375,"y":-0.032318115234375}],"optimisedCameraToObject":{"translation":{"x":-0.026556517013513734,"y":-0.09169131861072553,"z":0.44229082050746893},"rotation":{"quaternion":{"W":0.9988177619922952,"X":0.03444185215253263,"Y":-0.008801893988670333,"Z":0.033156655609667456}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":339.06060791015625,"y":292.2277526855469},{"x":376.3753967285156,"y":295.2994079589844},{"x":413.3639831542969,"y":298.71783447265625},{"x":450.476318359375,"y":301.5362854003906},{"x":486.95458984375,"y":304.9813537597656},{"x":523.896240234375,"y":308.00848388671875},{"x":559.9656982421875,"y":311.1206359863281},{"x":335.9451599121094,"y":329.9258117675781},{"x":373.13494873046875,"y":332.853759765625},{"x":410.1759033203125,"y":335.98614501953125},{"x":447.15313720703125,"y":338.95538330078125},{"x":483.89886474609375,"y":341.9346618652344},{"x":520.808349609375,"y":345.0412902832031},{"x":556.8765258789062,"y":347.9783020019531},{"x":332.4299621582031,"y":367.1687316894531},{"x":369.908203125,"y":370.0710144042969},{"x":406.8872985839844,"y":373.02349853515625},{"x":443.78204345703125,"y":376.0458068847656},{"x":480.3359375,"y":379.11102294921875},{"x":517.0509033203125,"y":382.09027099609375},{"x":553.3324584960938,"y":385.21063232421875},{"x":329.1856384277344,"y":404.4607238769531},{"x":366.669921875,"y":407.36090087890625},{"x":403.6183166503906,"y":410.22882080078125},{"x":440.5819396972656,"y":413.077392578125},{"x":477.1147766113281,"y":415.9818115234375},{"x":513.7654418945312,"y":419.2320251464844},{"x":550.2427978515625,"y":422.05621337890625},{"x":325.9815673828125,"y":441.2777099609375},{"x":363.1116638183594,"y":444.0122985839844},{"x":400.2497863769531,"y":447.0605773925781},{"x":437.31353759765625,"y":449.82061767578125},{"x":473.8950500488281,"y":452.83416748046875},{"x":510.6040344238281,"y":455.4580078125},{"x":547.0076293945312,"y":458.55987548828125},{"x":322.50762939453125,"y":478.7712707519531},{"x":360.0099792480469,"y":481.62567138671875},{"x":397.0208740234375,"y":484.18408203125},{"x":434.1093444824219,"y":486.8597717285156},{"x":470.58245849609375,"y":489.8636474609375},{"x":507.36163330078125,"y":492.8047790527344},{"x":543.9049682617188,"y":495.7187805175781},{"x":319.18109130859375,"y":515.9347534179688},{"x":356.81060791015625,"y":518.4778442382812},{"x":394.0828857421875,"y":521.1265869140625},{"x":430.8170471191406,"y":523.997802734375},{"x":467.4473876953125,"y":526.7676391601562},{"x":504.0103759765625,"y":529.2783813476562},{"x":540.6942749023438,"y":532.2147216796875}],"reprojectionErrors":[{"x":-0.121673583984375,"y":-0.06365966796875},{"x":-0.119964599609375,"y":0.112518310546875},{"x":0.042083740234375,"y":-0.0728759765625},{"x":-0.093109130859375,"y":0.3262939453125},{"x":0.224853515625,"y":0.082763671875},{"x":-0.10888671875,"y":0.240447998046875},{"x":0.2342529296875,"y":0.2957763671875},{"x":-0.24798583984375,"y":-0.375579833984375},{"x":-0.12652587890625,"y":-0.137237548828125},{"x":-0.021759033203125,"y":-0.120697021484375},{"x":-0.02642822265625,"y":0.041046142578125},{"x":0.019805908203125,"y":0.174163818359375},{"x":-0.28564453125,"y":0.1607666015625},{"x":0.05511474609375,"y":0.2972412109375},{"x":0.028106689453125,"y":-0.2608642578125},{"x":-0.14599609375,"y":-0.078460693359375},{"x":0.01385498046875,"y":0.033843994140625},{"x":0.085235595703125,"y":0.055816650390625},{"x":0.317230224609375,"y":0.01385498046875},{"x":0.2005615234375,"y":0.0362548828125},{"x":0.3226318359375,"y":-0.1046142578125},{"x":0.0364990234375,"y":-0.229339599609375},{"x":-0.15264892578125,"y":-0.12646484375},{"x":0.029266357421875,"y":-0.013763427734375},{"x":0.02349853515625,"y":0.095306396484375},{"x":0.268646240234375,"y":0.124969482421875},{"x":0.208740234375,"y":-0.215179443359375},{"x":0.12786865234375,"y":-0.153839111328125},{"x":0.00830078125,"y":0.23748779296875},{"x":0.1624755859375,"y":0.424346923828125},{"x":0.1441650390625,"y":0.272552490234375},{"x":0.02813720703125,"y":0.383453369140625},{"x":0.214874267578125,"y":0.21490478515625},{"x":0.08734130859375,"y":0.4095458984375},{"x":0.07122802734375,"y":0.0992431640625},{"x":0.254119873046875,"y":-0.017578125},{"x":0.023284912109375,"y":-0.0321044921875},{"x":0.119842529296875,"y":0.22186279296875},{"x":-0.0328369140625,"y":0.330535888671875},{"x":0.250762939453125,"y":0.082550048828125},{"x":0.0418701171875,"y":-0.131561279296875},{"x":-0.12469482421875,"y":-0.347869873046875},{"x":0.357147216796875,"y":0.006591796875},{"x":-0.015472412109375,"y":0.22186279296875},{"x":-0.19451904296875,"y":0.30145263671875},{"x":-0.00665283203125,"y":0.1280517578125},{"x":0.1063232421875,"y":0.025146484375},{"x":0.1007080078125,"y":0.1500244140625},{"x":-0.21893310546875,"y":-0.18243408203125}],"optimisedCameraToObject":{"translation":{"x":-0.04536870815710916,"y":-0.03017095703489484,"z":0.46287584605236204},"rotation":{"quaternion":{"W":0.9988271621016876,"X":0.004836541699075144,"Y":-0.020965421058413793,"Z":0.043374638120975896}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":221.30946350097656,"y":302.67108154296875},{"x":256.391357421875,"y":304.9172058105469},{"x":291.6982116699219,"y":307.3870849609375},{"x":327.6209411621094,"y":310.05615234375},{"x":363.8330078125,"y":313.071533203125},{"x":400.94366455078125,"y":315.8062744140625},{"x":438.015869140625,"y":318.3752746582031},{"x":218.8126983642578,"y":338.8110656738281},{"x":253.8575439453125,"y":341.3642578125},{"x":288.81927490234375,"y":343.9998779296875},{"x":324.8206787109375,"y":347.125244140625},{"x":361.1274108886719,"y":350.0592956542969},{"x":398.0586853027344,"y":353.0224914550781},{"x":435.3100891113281,"y":355.8133544921875},{"x":216.0008087158203,"y":374.9143981933594},{"x":250.92124938964844,"y":377.5718078613281},{"x":286.16070556640625,"y":380.89837646484375},{"x":322.10723876953125,"y":383.91717529296875},{"x":358.3690490722656,"y":387.3333740234375},{"x":395.28997802734375,"y":390.5809326171875},{"x":432.95025634765625,"y":394.11212158203125},{"x":213.41268920898438,"y":411.1982421875},{"x":248.2574462890625,"y":414.56072998046875},{"x":283.7270812988281,"y":417.9544982910156},{"x":319.26348876953125,"y":421.47296142578125},{"x":355.7355651855469,"y":425.0883483886719},{"x":392.7475280761719,"y":428.4670715332031},{"x":430.0685119628906,"y":431.9921875},{"x":210.95437622070312,"y":447.19818115234375},{"x":245.4503173828125,"y":450.7823486328125},{"x":280.9161682128906,"y":454.4261169433594},{"x":316.8917236328125,"y":458.3484802246094},{"x":352.9933166503906,"y":462.0141906738281},{"x":390.0523681640625,"y":465.77716064453125},{"x":427.4768981933594,"y":469.8221130371094},{"x":207.98121643066406,"y":483.9076843261719},{"x":242.7848358154297,"y":487.76690673828125},{"x":278.0449523925781,"y":491.8730163574219},{"x":314.2535400390625,"y":495.68414306640625},{"x":350.1916198730469,"y":499.61358642578125},{"x":387.3416442871094,"y":504.17822265625},{"x":424.7369079589844,"y":508.3167724609375},{"x":205.35462951660156,"y":520.1259155273438},{"x":239.98907470703125,"y":524.2392578125},{"x":275.2627868652344,"y":528.8871459960938},{"x":311.1852722167969,"y":532.9107055664062},{"x":347.7022705078125,"y":537.4143676757812},{"x":384.7498779296875,"y":541.8805541992188},{"x":421.8809814453125,"y":546.6923217773438}],"reprojectionErrors":[{"x":0.3195953369140625,"y":-0.011138916015625},{"x":-0.110565185546875,"y":0.24200439453125},{"x":-0.19647216796875,"y":0.312286376953125},{"x":-0.32354736328125,"y":0.224609375},{"x":-0.15972900390625,"y":-0.167724609375},{"x":-0.308929443359375,"y":-0.237396240234375},{"x":0.171173095703125,"y":-0.098907470703125},{"x":0.046295166015625,"y":-0.106048583984375},{"x":-0.3254852294921875,"y":0.130096435546875},{"x":-0.043701171875,"y":0.32659912109375},{"x":-0.225555419921875,"y":0.076507568359375},{"x":-0.13116455078125,"y":0.061279296875},{"x":-0.07440185546875,"y":0.060760498046875},{"x":0.2545166015625,"y":0.27679443359375},{"x":0.09356689453125,"y":-0.077392578125},{"x":-0.1340789794921875,"y":0.34588623046875},{"x":-0.10906982421875,"y":0.14471435546875},{"x":-0.213836669921875,"y":0.296356201171875},{"x":-0.051025390625,"y":0.096038818359375},{"x":0.040863037109375,"y":0.110076904296875},{"x":-0.012969970703125,"y":-0.113433837890625},{"x":-0.07708740234375,"y":-0.147247314453125},{"x":-0.2108917236328125,"y":-0.13653564453125},{"x":-0.396728515625,"y":-0.11041259765625},{"x":-0.07086181640625,"y":-0.162017822265625},{"x":-0.09661865234375,"y":-0.263214111328125},{"x":-0.072723388671875,"y":-0.08013916015625},{"x":0.23699951171875,"y":0.00445556640625},{"x":-0.3712615966796875,"y":0.14385986328125},{"x":-0.1396942138671875,"y":0.2265625},{"x":-0.3040771484375,"y":0.29827880859375},{"x":-0.3985595703125,"y":0.14031982421875},{"x":-0.033843994140625,"y":0.288238525390625},{"x":-0.035858154296875,"y":0.388427734375},{"x":0.192779541015625,"y":0.256439208984375},{"x":-0.143890380859375,"y":-0.202545166015625},{"x":-0.205047607421875,"y":-0.1002197265625},{"x":-0.147705078125,"y":-0.1942138671875},{"x":-0.458099365234375,"y":0.05767822265625},{"x":0.08837890625,"y":0.242431640625},{"x":0.0147705078125,"y":-0.156585693359375},{"x":0.293212890625,"y":-0.077880859375},{"x":-0.2559661865234375,"y":0.00933837890625},{"x":-0.134613037109375,"y":0.15313720703125},{"x":-0.076507568359375,"y":-0.18499755859375},{"x":-0.08538818359375,"y":0.154052734375},{"x":-0.10137939453125,"y":0.066162109375},{"x":-0.055023193359375,"y":0.06903076171875},{"x":0.506256103515625,"y":-0.22015380859375}],"optimisedCameraToObject":{"translation":{"x":-0.1290530628822834,"y":-0.022425294421625625,"z":0.4870023470641784},"rotation":{"quaternion":{"W":0.996613577856013,"X":-0.013464288198903548,"Y":0.07328200796996563,"Z":0.034782706683400264}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":90.03785705566406,"y":310.72601318359375},{"x":123.5698013305664,"y":312.5923767089844},{"x":157.36192321777344,"y":314.1973876953125},{"x":192.54029846191406,"y":316.1217346191406},{"x":227.55335998535156,"y":318.15032958984375},{"x":263.63360595703125,"y":319.9538879394531},{"x":299.928466796875,"y":322.12396240234375},{"x":88.27099609375,"y":347.0223693847656},{"x":121.81598663330078,"y":349.1436767578125},{"x":155.7424774169922,"y":351.2585754394531},{"x":190.23629760742188,"y":353.5048828125},{"x":225.2268524169922,"y":355.7200012207031},{"x":261.3660888671875,"y":358.1160583496094},{"x":297.9971008300781,"y":360.21441650390625},{"x":86.79167938232422,"y":383.2386779785156},{"x":120.0118408203125,"y":385.8603820800781},{"x":153.93344116210938,"y":388.2861633300781},{"x":188.90260314941406,"y":390.78948974609375},{"x":223.84828186035156,"y":393.1882019042969},{"x":259.80389404296875,"y":395.996826171875},{"x":296.0733642578125,"y":398.6301574707031},{"x":85.1788558959961,"y":419.8228759765625},{"x":118.29479217529297,"y":422.493408203125},{"x":152.09910583496094,"y":425.3936767578125},{"x":186.90147399902344,"y":428.1972351074219},{"x":221.836181640625,"y":431.2064208984375},{"x":257.70281982421875,"y":434.24017333984375},{"x":293.98223876953125,"y":437.14129638671875},{"x":83.60932159423828,"y":455.8818054199219},{"x":116.69644927978516,"y":458.8271789550781},{"x":150.2438507080078,"y":462.1194152832031},{"x":184.9669952392578,"y":465.1947937011719},{"x":220.1156463623047,"y":468.3623352050781},{"x":256.05645751953125,"y":471.8955383300781},{"x":292.100341796875,"y":475.28973388671875},{"x":81.90753173828125,"y":492.0986328125},{"x":114.95306396484375,"y":495.67340087890625},{"x":148.51992797851562,"y":499.0736083984375},{"x":183.3359375,"y":502.7611999511719},{"x":218.0794219970703,"y":506.5715637207031},{"x":253.9660186767578,"y":510.3570556640625},{"x":290.19189453125,"y":514.4142456054688},{"x":80.40311431884766,"y":528.0983276367188},{"x":113.1907958984375,"y":531.9303588867188},{"x":146.68115234375,"y":536.1470336914062},{"x":181.0702362060547,"y":540.0050048828125},{"x":216.1864013671875,"y":544.1866455078125},{"x":251.85195922851562,"y":548.3108520507812},{"x":288.1300354003906,"y":552.4865112304688}],"reprojectionErrors":[{"x":0.31475067138671875,"y":0.104095458984375},{"x":-0.05440521240234375,"y":0.0213623046875},{"x":-0.01019287109375,"y":0.234161376953125},{"x":-0.666748046875,"y":0.162384033203125},{"x":-0.46038818359375,"y":0.021728515625},{"x":-0.611358642578125,"y":0.14208984375},{"x":-0.254730224609375,"y":-0.067535400390625},{"x":0.26519012451171875,"y":0.00762939453125},{"x":-0.12104034423828125,"y":0.020904541015625},{"x":-0.2148895263671875,"y":0.078857421875},{"x":-0.190216064453125,"y":0.04425048828125},{"x":0.03570556640625,"y":0.080352783203125},{"x":-0.176849365234375,"y":-0.024383544921875},{"x":-0.15850830078125,"y":0.2093505859375},{"x":-0.05377197265625,"y":0.01678466796875},{"x":-0.12062835693359375,"y":-0.118927001953125},{"x":-0.2147674560546875,"y":-0.01641845703125},{"x":-0.670318603515625,"y":0.051544189453125},{"x":-0.40411376953125,"y":0.267730712890625},{"x":-0.437286376953125,"y":0.118316650390625},{"x":-0.061370849609375,"y":0.18914794921875},{"x":-0.2208099365234375,"y":-0.321502685546875},{"x":-0.1903228759765625,"y":-0.15435791015625},{"x":-0.1738433837890625,"y":-0.1705322265625},{"x":-0.46905517578125,"y":-0.042938232421875},{"x":-0.1980743408203125,"y":-0.073211669921875},{"x":-0.14825439453125,"y":-0.079559326171875},{"x":0.212066650390625,"y":0.095947265625},{"x":-0.4124298095703125,"y":-0.11932373046875},{"x":-0.36145782470703125,"y":0.12493896484375},{"x":-0.096221923828125,"y":0.07275390625},{"x":-0.3202056884765625,"y":0.28863525390625},{"x":-0.2710113525390625,"y":0.464263916015625},{"x":-0.3029937744140625,"y":0.326904296875},{"x":0.285400390625,"y":0.3819580078125},{"x":-0.4528350830078125,"y":-0.06500244140625},{"x":-0.37000274658203125,"y":-0.098114013671875},{"x":-0.133880615234375,"y":0.09783935546875},{"x":-0.460296630859375,"y":0.06170654296875},{"x":-0.015380859375,"y":-0.041107177734375},{"x":-0.002471923828125,"y":-0.062225341796875},{"x":0.39471435546875,"y":-0.29736328125},{"x":-0.67138671875,"y":0.21124267578125},{"x":-0.3418731689453125,"y":0.27288818359375},{"x":-0.040374755859375,"y":0.00848388671875},{"x":0.049041748046875,"y":0.1622314453125},{"x":0.1102142333984375,"y":0.052490234375},{"x":0.3331298828125,"y":0.06121826171875},{"x":0.667144775390625,"y":0.080322265625}],"optimisedCameraToObject":{"translation":{"x":-0.22137176650342022,"y":-0.016187657334579206,"z":0.48572507003640303},"rotation":{"quaternion":{"W":0.9957062261574929,"X":-0.005003618327433362,"Y":0.08952528061073889,"Z":0.02300650182894953}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":100.60881805419922,"y":106.35810852050781},{"x":134.24545288085938,"y":105.85897064208984},{"x":168.5045166015625,"y":105.46611785888672},{"x":203.2729949951172,"y":105.12342071533203},{"x":238.26821899414062,"y":104.8594970703125},{"x":273.5412902832031,"y":104.19483947753906},{"x":309.02447509765625,"y":103.86144256591797},{"x":103.160400390625,"y":142.52784729003906},{"x":137.10281372070312,"y":142.42019653320312},{"x":171.01174926757812,"y":142.2108917236328},{"x":205.05389404296875,"y":142.06207275390625},{"x":239.34983825683594,"y":141.52191162109375},{"x":274.89947509765625,"y":141.5987548828125},{"x":309.9424743652344,"y":141.15638732910156},{"x":106.41924285888672,"y":178.23939514160156},{"x":139.53018188476562,"y":178.255615234375},{"x":173.10044860839844,"y":178.14947509765625},{"x":207.24412536621094,"y":178.1393280029297},{"x":241.2316131591797,"y":178.1968994140625},{"x":275.9998474121094,"y":178.00994873046875},{"x":310.8657531738281,"y":178.0529022216797},{"x":109.19105529785156,"y":213.11158752441406},{"x":142.28549194335938,"y":213.2199249267578},{"x":175.31932067871094,"y":213.21669006347656},{"x":209.052734375,"y":213.772705078125},{"x":242.93116760253906,"y":213.88784790039062},{"x":277.0687255859375,"y":213.8684844970703},{"x":311.75323486328125,"y":213.96372985839844},{"x":112.26685333251953,"y":246.92816162109375},{"x":144.78172302246094,"y":247.1885528564453},{"x":177.6352996826172,"y":247.8976593017578},{"x":211.0437469482422,"y":248.02745056152344},{"x":244.48867797851562,"y":248.15513610839844},{"x":278.5101318359375,"y":248.3973388671875},{"x":312.2657165527344,"y":248.80703735351562},{"x":114.79291534423828,"y":280.9228820800781},{"x":147.14212036132812,"y":281.2057189941406},{"x":179.7499237060547,"y":281.90570068359375},{"x":212.89447021484375,"y":282.06036376953125},{"x":245.861083984375,"y":282.670654296875},{"x":279.33526611328125,"y":283.0027160644531},{"x":313.04229736328125,"y":283.33135986328125},{"x":117.60826110839844,"y":313.4248352050781},{"x":149.4197998046875,"y":314.0152893066406},{"x":181.60345458984375,"y":314.96502685546875},{"x":214.1979522705078,"y":315.2834167480469},{"x":247.1965789794922,"y":315.859619140625},{"x":280.1527099609375,"y":316.1675720214844},{"x":313.9950866699219,"y":316.99908447265625}],"reprojectionErrors":[{"x":-0.23943328857421875,"y":0.1803131103515625},{"x":-0.0606231689453125,"y":0.22280120849609375},{"x":-0.10491943359375,"y":0.15741729736328125},{"x":-0.2601776123046875,"y":0.04036712646484375},{"x":-0.244842529296875,"y":-0.15688323974609375},{"x":-0.11126708984375,"y":0.04524993896484375},{"x":0.206787109375,"y":-0.08514404296875},{"x":0.1674041748046875,"y":0.2610321044921875},{"x":-0.291595458984375,"y":0.116668701171875},{"x":-0.3257904052734375,"y":0.0720062255859375},{"x":-0.102783203125,"y":-0.0350494384765625},{"x":0.255706787109375,"y":0.247314453125},{"x":-0.25152587890625,"y":-0.0891876220703125},{"x":0.13427734375,"y":0.0916748046875},{"x":-0.17758941650390625,"y":0.0635833740234375},{"x":-0.13214111328125,"y":-0.0081939697265625},{"x":-0.1624755859375,"y":0.0400390625},{"x":-0.383636474609375,"y":-0.0100860595703125},{"x":-0.0671844482421875,"y":-0.1303253173828125},{"x":-0.15142822265625,"y":-0.0084686279296875},{"x":0.045166015625,"y":-0.11895751953125},{"x":-0.0791778564453125,"y":-0.01336669921875},{"x":-0.3393402099609375,"y":0.0113067626953125},{"x":-0.162933349609375,"y":0.1447906494140625},{"x":-0.3111419677734375,"y":-0.2838134765625},{"x":-0.230621337890625,"y":-0.274444580078125},{"x":-0.036865234375,"y":-0.1335601806640625},{"x":-0.019287109375,"y":-0.1103363037109375},{"x":-0.32744598388671875,"y":0.2634124755859375},{"x":-0.325347900390625,"y":0.317047119140625},{"x":-0.293365478515625,"y":-0.0812530517578125},{"x":-0.4487457275390625,"y":0.0964508056640625},{"x":-0.2743072509765625,"y":0.2728118896484375},{"x":-0.311553955078125,"y":0.3311004638671875},{"x":0.28033447265625,"y":0.2182159423828125},{"x":-0.0677642822265625,"y":-0.3233642578125},{"x":-0.21258544921875,"y":-0.118438720703125},{"x":-0.2546234130859375,"y":-0.3343505859375},{"x":-0.4731292724609375,"y":-0.008758544921875},{"x":-0.154693603515625,"y":-0.142791748046875},{"x":0.01373291015625,"y":-0.00274658203125},{"x":0.305206298828125,"y":0.13641357421875},{"x":-0.138275146484375,"y":-0.08673095703125},{"x":-0.0533905029296875,"y":-0.022705078125},{"x":0.0137176513671875,"y":-0.322113037109375},{"x":0.023193359375,"y":0.005462646484375},{"x":-0.0195159912109375,"y":0.0706787109375},{"x":0.3306884765625,"y":0.3994140625},{"x":0.1434326171875,"y":0.199615478515625}],"optimisedCameraToObject":{"translation":{"x":-0.22047385850192655,"y":-0.1614092023625872,"z":0.4899358736118981},"rotation":{"quaternion":{"W":0.9933996380171577,"X":0.10172414109068803,"Y":0.05293082786767422,"Z":0.0027723217678596816}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":243.2695770263672,"y":81.22762298583984},{"x":279.8285217285156,"y":82.23822784423828},{"x":316.10614013671875,"y":83.77398681640625},{"x":352.95391845703125,"y":84.47020721435547},{"x":389.87567138671875,"y":85.77462005615234},{"x":427.1100158691406,"y":86.99259185791016},{"x":464.104736328125,"y":87.92891693115234},{"x":243.7480926513672,"y":119.14984130859375},{"x":279.82269287109375,"y":120.49337005615234},{"x":315.6341552734375,"y":121.35456085205078},{"x":351.994384765625,"y":123.01411437988281},{"x":388.28546142578125,"y":123.7025146484375},{"x":425.20965576171875,"y":125.00679016113281},{"x":461.677978515625,"y":126.26045989990234},{"x":244.11563110351562,"y":156.4071807861328},{"x":279.2550048828125,"y":157.36131286621094},{"x":315.2771911621094,"y":158.77676391601562},{"x":351.260986328125,"y":160.11602783203125},{"x":387.0486755371094,"y":161.2786407470703},{"x":423.3376770019531,"y":162.6897430419922},{"x":459.3424072265625,"y":163.77529907226562},{"x":244.7848663330078,"y":193.2002410888672},{"x":279.6170349121094,"y":194.09181213378906},{"x":314.87432861328125,"y":195.18780517578125},{"x":350.1983947753906,"y":196.8892364501953},{"x":385.9397277832031,"y":197.94764709472656},{"x":421.71514892578125,"y":199.32228088378906},{"x":457.51824951171875,"y":200.42483520507812},{"x":244.8019256591797,"y":227.90902709960938},{"x":279.4519958496094,"y":229.16551208496094},{"x":314.3529357910156,"y":230.55235290527344},{"x":349.50048828125,"y":231.98866271972656},{"x":384.7686462402344,"y":233.32591247558594},{"x":419.96533203125,"y":234.4287109375},{"x":455.4043273925781,"y":235.98060607910156},{"x":245.040771484375,"y":262.8219299316406},{"x":279.5098876953125,"y":264.1510314941406},{"x":313.92010498046875,"y":265.491943359375},{"x":348.6171569824219,"y":266.93072509765625},{"x":383.2054138183594,"y":268.17816162109375},{"x":418.552490234375,"y":269.893310546875},{"x":453.0155029296875,"y":271.1266174316406},{"x":245.32965087890625,"y":296.3208312988281},{"x":279.263916015625,"y":297.9762268066406},{"x":313.22088623046875,"y":299.5179748535156},{"x":347.82318115234375,"y":300.820068359375},{"x":382.0979919433594,"y":302.2673645019531},{"x":416.7114562988281,"y":303.8325500488281},{"x":451.2049255371094,"y":305.44207763671875}],"reprojectionErrors":[{"x":0.012115478515625,"y":0.350250244140625},{"x":-0.187957763671875,"y":0.3769073486328125},{"x":0.09002685546875,"y":-0.11165618896484375},{"x":-0.01226806640625,"y":0.24908447265625},{"x":-0.005584716796875,"y":0.01122283935546875},{"x":-0.135650634765625,"y":-0.130767822265625},{"x":0.1424560546875,"y":0.01811981201171875},{"x":-0.143280029296875,"y":0.30511474609375},{"x":-0.276947021484375,"y":0.08429718017578125},{"x":0.044830322265625,"y":0.3532257080078125},{"x":0.003509521484375,"y":-0.16898345947265625},{"x":0.210174560546875,"y":0.28696441650390625},{"x":-0.044403076171875,"y":0.13384246826171875},{"x":0.321685791015625,"y":0.0379180908203125},{"x":-0.1872406005859375,"y":0.0638275146484375},{"x":0.204193115234375,"y":0.31365966796875},{"x":-0.09912109375,"y":0.107177734375},{"x":-0.1824951171875,"y":-0.0183563232421875},{"x":0.1051025390625,"y":0.03729248046875},{"x":0.059417724609375,"y":-0.1512603759765625},{"x":0.459136962890625,"y":-0.0102081298828125},{"x":-0.5325164794921875,"y":-0.5502471923828125},{"x":-0.236328125,"y":-0.1605987548828125},{"x":-0.181365966796875,"y":0.0272979736328125},{"x":-0.015625,"y":-0.3878173828125},{"x":-0.09613037109375,"y":-0.1577606201171875},{"x":-0.046417236328125,"y":-0.242034912109375},{"x":0.133148193359375,"y":-0.0526275634765625},{"x":-0.22528076171875,"y":0.10601806640625},{"x":-0.14202880859375,"y":0.2041778564453125},{"x":-0.1297607421875,"y":0.1724395751953125},{"x":-0.1904296875,"y":0.091400146484375},{"x":-0.2044677734375,"y":0.109283447265625},{"x":0.013702392578125,"y":0.3612060546875},{"x":0.14361572265625,"y":0.163299560546875},{"x":-0.1395416259765625,"y":-0.23345947265625},{"x":-0.263153076171875,"y":-0.138153076171875},{"x":-0.151824951171875,"y":-0.056304931640625},{"x":-0.157470703125,"y":-0.0743408203125},{"x":0.109283447265625,"y":0.0966796875},{"x":-0.22552490234375,"y":-0.202667236328125},{"x":0.474395751953125,"y":-0.023162841796875},{"x":-0.103607177734375,"y":0.070953369140625},{"x":-0.0731201171875,"y":-0.09368896484375},{"x":0.106903076171875,"y":-0.1484375},{"x":-0.192169189453125,"y":0.03240966796875},{"x":-0.003662109375,"y":0.0635986328125},{"x":-3.0517578125E-5,"y":-0.02783203125},{"x":0.27105712890625,"y":-0.168701171875}],"optimisedCameraToObject":{"translation":{"x":-0.11356671383887333,"y":-0.17429860638544456,"z":0.47012122146438},"rotation":{"quaternion":{"W":0.9934764829645861,"X":0.10966589947086226,"Y":0.025040246152755383,"Z":0.0187311068058632}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":367.2918395996094,"y":67.62530517578125},{"x":404.6898498535156,"y":69.92713928222656},{"x":442.1222229003906,"y":72.81950378417969},{"x":479.8296203613281,"y":75.34724426269531},{"x":517.5645751953125,"y":78.1654281616211},{"x":556.0475463867188,"y":80.80663299560547},{"x":594.6295166015625,"y":83.26685333251953},{"x":364.4712219238281,"y":106.00704193115234},{"x":401.33514404296875,"y":109.02845001220703},{"x":438.1849670410156,"y":111.73956298828125},{"x":475.8946228027344,"y":114.54194641113281},{"x":513.2501220703125,"y":117.01956939697266},{"x":551.0753784179688,"y":120.0047378540039},{"x":589.084228515625,"y":122.37987518310547},{"x":361.7715759277344,"y":144.1632537841797},{"x":397.8608093261719,"y":146.83489990234375},{"x":434.76806640625,"y":149.7847900390625},{"x":471.6131591796875,"y":152.58998107910156},{"x":508.7997741699219,"y":155.4178466796875},{"x":546.2542724609375,"y":158.08352661132812},{"x":583.8139038085938,"y":161.015869140625},{"x":359.132568359375,"y":181.45274353027344},{"x":394.9653015136719,"y":184.33155822753906},{"x":431.1470031738281,"y":187.2745819091797},{"x":467.7469177246094,"y":190.042724609375},{"x":504.3866271972656,"y":193.1957550048828},{"x":541.4052124023438,"y":196.06007385253906},{"x":578.7274780273438,"y":198.92942810058594},{"x":356.830322265625,"y":217.109375},{"x":391.8899230957031,"y":219.993896484375},{"x":427.86236572265625,"y":223.025634765625},{"x":464.0811462402344,"y":226.20985412597656},{"x":500.2019958496094,"y":229.1658172607422},{"x":537.0227661132812,"y":232.20359802246094},{"x":573.9921875,"y":235.30296325683594},{"x":354.0520935058594,"y":252.7326202392578},{"x":389.0713195800781,"y":255.83079528808594},{"x":424.4225769042969,"y":258.8902893066406},{"x":460.4226989746094,"y":261.8040466308594},{"x":495.9723815917969,"y":265.1920471191406},{"x":532.4160766601562,"y":268.47662353515625},{"x":568.7553100585938,"y":271.8113098144531},{"x":351.797607421875,"y":287.0257873535156},{"x":386.207763671875,"y":290.1442565917969},{"x":421.3124084472656,"y":293.720947265625},{"x":456.5373229980469,"y":297.0552978515625},{"x":491.90625,"y":300.28033447265625},{"x":528.0879516601562,"y":303.6836853027344},{"x":564.2083129882812,"y":306.9112548828125}],"reprojectionErrors":[{"x":-0.168426513671875,"y":0.04798126220703125},{"x":-0.345947265625,"y":0.32196044921875},{"x":-0.26434326171875,"y":0.03229522705078125},{"x":-0.16961669921875,"y":0.13384246826171875},{"x":0.18023681640625,"y":-0.0287628173828125},{"x":0.05902099609375,"y":0.01155853271484375},{"x":0.1097412109375,"y":0.25849151611328125},{"x":-0.116363525390625,"y":0.27032470703125},{"x":-0.17864990234375,"y":-0.05319976806640625},{"x":0.0604248046875,"y":-0.04186248779296875},{"x":-0.278350830078125,"y":-0.09755706787109375},{"x":0.013671875,"y":0.19538116455078125},{"x":0.10687255859375,"y":0.0042724609375},{"x":0.2816162109375,"y":0.44629669189453125},{"x":-0.122039794921875,"y":-0.1152801513671875},{"x":0.1790771484375,"y":0.0270233154296875},{"x":-0.056640625,"y":-0.086578369140625},{"x":0.04583740234375,"y":-0.033538818359375},{"x":0.077545166015625,"y":0.0183563232421875},{"x":0.1065673828125,"y":0.2535552978515625},{"x":0.28985595703125,"y":0.242767333984375},{"x":-0.126800537109375,"y":-0.4461822509765625},{"x":0.026885986328125,"y":-0.4007110595703125},{"x":0.10693359375,"y":-0.3992919921875},{"x":0.039031982421875,"y":-0.2032623291015625},{"x":0.196319580078125,"y":-0.37286376953125},{"x":0.23431396484375,"y":-0.2349395751953125},{"x":0.22247314453125,"y":-0.0837249755859375},{"x":-0.408355712890625,"y":0.0645294189453125},{"x":0.12176513671875,"y":0.209136962890625},{"x":0.008636474609375,"y":0.2245941162109375},{"x":-0.08624267578125,"y":0.1051177978515625},{"x":0.176300048828125,"y":0.2309722900390625},{"x":-0.00701904296875,"y":0.2915802001953125},{"x":-0.0904541015625,"y":0.3066558837890625},{"x":-0.155517578125,"y":-0.1625213623046875},{"x":0.025299072265625,"y":-0.1319580078125},{"x":0.138092041015625,"y":-0.046722412109375},{"x":-0.13885498046875,"y":0.199737548828125},{"x":0.288665771484375,"y":-0.01312255859375},{"x":0.07098388671875,"y":-0.108154296875},{"x":0.2010498046875,"y":-0.23944091796875},{"x":-0.369476318359375,"y":0.1888427734375},{"x":0.03753662109375,"y":0.293701171875},{"x":0.0086669921875,"y":-0.045684814453125},{"x":0.113311767578125,"y":-0.1292724609375},{"x":0.32275390625,"y":-0.090667724609375},{"x":-0.0369873046875,"y":-0.21807861328125},{"x":-0.09710693359375,"y":-0.157989501953125}],"optimisedCameraToObject":{"translation":{"x":-0.02648596589479527,"y":-0.18232819878905754,"z":0.4625163563911466},"rotation":{"quaternion":{"W":0.9931983687342055,"X":0.1011753142795983,"Y":0.03909697172846946,"Z":0.04233181930653161}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":482.02740478515625,"y":67.85414123535156},{"x":519.1791381835938,"y":70.19827270507812},{"x":557.405029296875,"y":73.2572250366211},{"x":596.852783203125,"y":76.17818450927734},{"x":637.25341796875,"y":79.53508758544922},{"x":678.9290161132812,"y":82.88789367675781},{"x":721.172607421875,"y":86.3917236328125},{"x":476.3291015625,"y":105.80760955810547},{"x":513.3225708007812,"y":109.00564575195312},{"x":550.8635864257812,"y":112.14144134521484},{"x":590.0658569335938,"y":115.8410873413086},{"x":629.9588623046875,"y":119.335693359375},{"x":671.113525390625,"y":123.41663360595703},{"x":713.154541015625,"y":127.07598114013672},{"x":471.04571533203125,"y":142.9325714111328},{"x":507.3626403808594,"y":147.03160095214844},{"x":544.5314331054688,"y":150.8074951171875},{"x":583.296142578125,"y":154.7140350341797},{"x":622.63232421875,"y":158.91746520996094},{"x":663.1920776367188,"y":163.245849609375},{"x":704.9970092773438,"y":167.42636108398438},{"x":465.7544860839844,"y":179.81497192382812},{"x":501.59136962890625,"y":184.14988708496094},{"x":538.6113891601562,"y":188.17022705078125},{"x":576.569091796875,"y":193.0123748779297},{"x":615.66650390625,"y":197.40896606445312},{"x":655.939208984375,"y":202.4432830810547},{"x":696.8970336914062,"y":206.7740020751953},{"x":460.8822021484375,"y":215.2262725830078},{"x":496.1688232421875,"y":219.8177947998047},{"x":532.490478515625,"y":224.7072296142578},{"x":570.2700805664062,"y":229.562255859375},{"x":608.61279296875,"y":234.74713134765625},{"x":648.3853759765625,"y":239.83773803710938},{"x":689.23779296875,"y":245.4080810546875},{"x":455.7551574707031,"y":250.49452209472656},{"x":491.04547119140625,"y":255.74461364746094},{"x":526.4088134765625,"y":260.80694580078125},{"x":563.9888916015625,"y":266.3124694824219},{"x":601.850341796875,"y":271.900390625},{"x":641.2565307617188,"y":277.5727844238281},{"x":681.3260498046875,"y":283.3553771972656},{"x":450.9871520996094,"y":284.8897705078125},{"x":485.68463134765625,"y":290.39886474609375},{"x":521.0753784179688,"y":296.0263366699219},{"x":557.8743896484375,"y":301.7718811035156},{"x":595.37109375,"y":307.8623962402344},{"x":634.2429809570312,"y":313.9140319824219},{"x":673.9807739257812,"y":320.4443359375}],"reprojectionErrors":[{"x":-0.491119384765625,"y":-0.38817596435546875},{"x":-0.38067626953125,"y":0.161895751953125},{"x":-0.2926025390625,"y":0.087646484375},{"x":-0.33868408203125,"y":0.24506378173828125},{"x":-0.2122802734375,"y":0.06351470947265625},{"x":-0.19622802734375,"y":-0.01349639892578125},{"x":0.45733642578125,"y":-0.13748931884765625},{"x":-0.14837646484375,"y":-0.33753204345703125},{"x":-0.32159423828125,"y":-0.1468048095703125},{"x":-0.0130615234375,"y":0.206634521484375},{"x":-0.30157470703125,"y":0.10013580322265625},{"x":-0.180419921875,"y":0.306182861328125},{"x":-0.1826171875,"y":0.03714752197265625},{"x":0.106689453125,"y":0.30487823486328125},{"x":-0.112518310546875,"y":-0.1899566650390625},{"x":-0.042755126953125,"y":-0.425506591796875},{"x":0.18267822265625,"y":-0.2281646728515625},{"x":-0.1466064453125,"y":-0.04803466796875},{"x":0.0289306640625,"y":-0.047515869140625},{"x":0.09368896484375,"y":-0.0506744384765625},{"x":0.0643310546875,"y":0.219512939453125},{"x":0.036773681640625,"y":-0.515472412109375},{"x":0.161224365234375,"y":-0.5312652587890625},{"x":0.0888671875,"y":-0.1141204833984375},{"x":0.0977783203125,"y":-0.3965301513671875},{"x":0.01971435546875,"y":-0.1070404052734375},{"x":-0.1455078125,"y":-0.32470703125},{"x":0.12908935546875,"y":0.29620361328125},{"x":-0.12957763671875,"y":-0.0699615478515625},{"x":0.12774658203125,"y":0.0948486328125},{"x":0.3157958984375,"y":0.0881195068359375},{"x":0.0430908203125,"y":0.246246337890625},{"x":0.2373046875,"y":0.2092437744140625},{"x":0.065673828125,"y":0.4056549072265625},{"x":-0.08612060546875,"y":0.26611328125},{"x":0.059844970703125,"y":-0.1663665771484375},{"x":-0.096099853515625,"y":-0.240631103515625},{"x":0.62060546875,"y":0.006622314453125},{"x":0.09674072265625,"y":-0.05126953125},{"x":0.29925537109375,"y":-0.049102783203125},{"x":-0.002197265625,"y":0.01568603515625},{"x":0.10809326171875,"y":0.122161865234375},{"x":-0.010955810546875,"y":-0.059967041015625},{"x":0.02392578125,"y":0.0091552734375},{"x":0.29168701171875,"y":0.10052490234375},{"x":0.10687255859375,"y":0.2188720703125},{"x":0.2105712890625,"y":0.141876220703125},{"x":-0.04278564453125,"y":0.25811767578125},{"x":-0.11083984375,"y":0.0550537109375}],"optimisedCameraToObject":{"translation":{"x":0.054151361053929314,"y":-0.1858468240620645,"z":0.4725195135072814},"rotation":{"quaternion":{"W":0.9849507004338287,"X":0.08391289301021776,"Y":0.13360726023493064,"Z":0.07056801055776961}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":519.5244140625,"y":245.12351989746094},{"x":558.471923828125,"y":251.675048828125},{"x":596.7239990234375,"y":257.7232360839844},{"x":635.6854858398438,"y":263.98468017578125},{"x":674.5379028320312,"y":270.32366943359375},{"x":713.6610717773438,"y":276.7524108886719},{"x":752.1699829101562,"y":283.218505859375},{"x":512.980224609375,"y":283.0467529296875},{"x":551.4111938476562,"y":289.54351806640625},{"x":589.6847534179688,"y":295.5984191894531},{"x":628.8233032226562,"y":302.40472412109375},{"x":667.6785278320312,"y":308.7755432128906},{"x":706.1992797851562,"y":315.4500427246094},{"x":744.8543090820312,"y":321.6322937011719},{"x":505.95404052734375,"y":321.15545654296875},{"x":544.0733642578125,"y":327.5103454589844},{"x":582.5726318359375,"y":333.92938232421875},{"x":621.123779296875,"y":340.270751953125},{"x":659.8519897460938,"y":346.8523254394531},{"x":698.9984130859375,"y":353.3747863769531},{"x":737.465576171875,"y":360.04595947265625},{"x":499.17425537109375,"y":358.8080139160156},{"x":537.33056640625,"y":365.2261962890625},{"x":575.4298706054688,"y":371.4945373535156},{"x":614.0624389648438,"y":378.6170654296875},{"x":652.7932739257812,"y":385.22918701171875},{"x":691.76416015625,"y":391.7854309082031},{"x":730.0270385742188,"y":398.1099853515625},{"x":492.56658935546875,"y":395.71905517578125},{"x":530.6734008789062,"y":402.3073425292969},{"x":568.4944458007812,"y":409.10186767578125},{"x":607.2514038085938,"y":415.79791259765625},{"x":645.548095703125,"y":422.4119567871094},{"x":684.2268676757812,"y":428.8694152832031},{"x":723.0330810546875,"y":435.78070068359375},{"x":485.85308837890625,"y":433.1748962402344},{"x":523.7552490234375,"y":440.01055908203125},{"x":561.7548217773438,"y":446.6956481933594},{"x":600.1557006835938,"y":453.33441162109375},{"x":638.3101196289062,"y":460.0498352050781},{"x":677.0709228515625,"y":467.0345153808594},{"x":715.3709106445312,"y":473.7884521484375},{"x":479.2823181152344,"y":469.9844970703125},{"x":517.0146484375,"y":476.75030517578125},{"x":555.22998046875,"y":483.81219482421875},{"x":593.109130859375,"y":490.187744140625},{"x":631.504150390625,"y":497.5484619140625},{"x":669.8975219726562,"y":504.2423095703125},{"x":708.2178955078125,"y":511.0511474609375}],"reprojectionErrors":[{"x":0.11614990234375,"y":-0.254241943359375},{"x":-0.3385009765625,"y":-0.45989990234375},{"x":0.067626953125,"y":-0.13177490234375},{"x":-0.07867431640625,"y":0.01220703125},{"x":0.03265380859375,"y":0.1063232421875},{"x":0.01312255859375,"y":0.136993408203125},{"x":0.73895263671875,"y":0.155181884765625},{"x":-0.10357666015625,"y":-0.041595458984375},{"x":-0.16766357421875,"y":-0.121429443359375},{"x":0.09051513671875,"y":0.2681884765625},{"x":-0.3597412109375,"y":-0.067413330078125},{"x":-0.37847900390625,"y":0.0572509765625},{"x":0.07672119140625,"y":-0.098419189453125},{"x":0.528564453125,"y":0.260040283203125},{"x":0.191925048828125,"y":-0.23443603515625},{"x":0.31231689453125,"y":-0.102569580078125},{"x":0.2171630859375,"y":-0.0101318359375},{"x":0.2261962890625,"y":0.18328857421875},{"x":0.2059326171875,"y":0.158416748046875},{"x":-0.0933837890625,"y":0.21307373046875},{"x":0.4171142578125,"y":0.137969970703125},{"x":0.274993896484375,"y":-0.195037841796875},{"x":0.2301025390625,"y":-0.057952880859375},{"x":0.40606689453125,"y":0.25091552734375},{"x":0.20440673828125,"y":-0.27392578125},{"x":0.05181884765625,"y":-0.269317626953125},{"x":-0.2020263671875,"y":-0.191314697265625},{"x":0.38238525390625,"y":0.1343994140625},{"x":0.22064208984375,"y":0.358062744140625},{"x":0.09588623046875,"y":0.392333984375},{"x":0.420166015625,"y":0.239501953125},{"x":-0.03631591796875,"y":0.20281982421875},{"x":0.11431884765625,"y":0.26434326171875},{"x":0.0213623046875,"y":0.49713134765625},{"x":-0.069091796875,"y":0.2891845703125},{"x":0.307586669921875,"y":0.134918212890625},{"x":0.2569580078125,"y":-0.012237548828125},{"x":0.27166748046875,"y":0.007598876953125},{"x":0.03973388671875,"y":0.08868408203125},{"x":0.20068359375,"y":0.106475830078125},{"x":-0.106689453125,"y":-0.133148193359375},{"x":0.1763916015625,"y":-0.13177490234375},{"x":0.28790283203125,"y":0.3228759765625},{"x":0.27557373046875,"y":0.310302734375},{"x":-0.0576171875,"y":0.01531982421875},{"x":0.09954833984375,"y":0.4188232421875},{"x":-0.1131591796875,"y":-0.1522216796875},{"x":-0.18658447265625,"y":-0.04736328125},{"x":-0.0577392578125,"y":-0.050048828125}],"optimisedCameraToObject":{"translation":{"x":0.07634276098870524,"y":-0.06291076841626946,"z":0.45015164748900965},"rotation":{"quaternion":{"W":0.9960034574789867,"X":0.024613647352990743,"Y":0.021443639868140046,"Z":0.08313513915963891}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":130.29617309570312,"y":249.16114807128906},{"x":163.83306884765625,"y":252.67201232910156},{"x":198.07093811035156,"y":256.255126953125},{"x":233.09371948242188,"y":260.1888122558594},{"x":268.87518310546875,"y":264.0448303222656},{"x":305.1092834472656,"y":267.8274841308594},{"x":341.9736022949219,"y":271.7432556152344},{"x":129.827880859375,"y":285.33660888671875},{"x":163.10235595703125,"y":289.0769348144531},{"x":196.822265625,"y":293.134765625},{"x":231.08750915527344,"y":297.2909851074219},{"x":266.2427062988281,"y":300.921630859375},{"x":302.7452392578125,"y":305.586669921875},{"x":339.181640625,"y":309.7203674316406},{"x":129.23135375976562,"y":320.7911071777344},{"x":162.02432250976562,"y":324.95709228515625},{"x":195.8250274658203,"y":328.9322204589844},{"x":229.88400268554688,"y":333.31048583984375},{"x":264.8960876464844,"y":337.78515625},{"x":300.0954895019531,"y":342.4007568359375},{"x":336.4063415527344,"y":346.95745849609375},{"x":128.90687561035156,"y":355.5209655761719},{"x":161.13555908203125,"y":360.02227783203125},{"x":194.13937377929688,"y":364.622802734375},{"x":228.11398315429688,"y":369.44232177734375},{"x":262.816650390625,"y":374.0978088378906},{"x":297.74072265625,"y":379.30499267578125},{"x":333.7509765625,"y":383.5601501464844},{"x":128.35232543945312,"y":389.3068542480469},{"x":160.23255920410156,"y":394.2916259765625},{"x":193.2902069091797,"y":398.9712829589844},{"x":226.87437438964844,"y":404.19024658203125},{"x":260.82757568359375,"y":409.2768859863281},{"x":295.972412109375,"y":414.0907897949219},{"x":331.1429443359375,"y":419.7847900390625},{"x":127.55606842041016,"y":423.3240051269531},{"x":159.58749389648438,"y":428.47296142578125},{"x":192.0301055908203,"y":433.5769958496094},{"x":225.45359802246094,"y":438.7577209472656},{"x":258.9909362792969,"y":444.1112060546875},{"x":293.7815246582031,"y":449.9676818847656},{"x":328.56982421875,"y":455.7482604980469},{"x":127.20055389404297,"y":456.12188720703125},{"x":158.61007690429688,"y":461.47711181640625},{"x":190.50961303710938,"y":467.2626647949219},{"x":223.7522430419922,"y":472.83428955078125},{"x":257.1024169921875,"y":478.5074768066406},{"x":291.06451416015625,"y":483.9815368652344},{"x":326.1264343261719,"y":490.3427429199219}],"reprojectionErrors":[{"x":0.30828857421875,"y":0.2195892333984375},{"x":0.065460205078125,"y":0.2335205078125},{"x":-0.1358795166015625,"y":0.246429443359375},{"x":-0.363372802734375,"y":-0.0185546875},{"x":-0.574127197265625,"y":-0.13165283203125},{"x":-0.445068359375,"y":-0.0955810546875},{"x":-0.13641357421875,"y":-0.11529541015625},{"x":0.064056396484375,"y":0.0189208984375},{"x":-0.2126922607421875,"y":0.15325927734375},{"x":-0.2051544189453125,"y":0.045440673828125},{"x":0.0025634765625,"y":-0.083953857421875},{"x":0.08203125,"y":0.390655517578125},{"x":-0.40765380859375,"y":-0.089111328125},{"x":-0.036163330078125,"y":0.044036865234375},{"x":-0.02154541015625,"y":-0.0791015625},{"x":-0.1092681884765625,"y":-0.033203125},{"x":-0.4874725341796875,"y":0.28265380859375},{"x":-0.391387939453125,"y":0.27606201171875},{"x":-0.5001220703125,"y":0.25537109375},{"x":-0.031951904296875,"y":0.1776123046875},{"x":0.1053466796875,"y":0.24432373046875},{"x":-0.349517822265625,"y":-0.059906005859375},{"x":-0.161590576171875,"y":-0.02447509765625},{"x":-0.043792724609375,"y":-0.005615234375},{"x":-0.1768951416015625,"y":-0.121490478515625},{"x":-0.30291748046875,"y":0.01251220703125},{"x":0.100250244140625,"y":-0.317657470703125},{"x":0.1837158203125,"y":0.393341064453125},{"x":-0.418365478515625,"y":0.306427001953125},{"x":-0.1669158935546875,"y":0.171356201171875},{"x":-0.3998260498046875,"y":0.42730712890625},{"x":-0.451751708984375,"y":0.231475830078125},{"x":-0.15045166015625,"y":0.257110595703125},{"x":-0.30352783203125,"y":0.64630126953125},{"x":0.270355224609375,"y":0.247894287109375},{"x":-0.2171173095703125,"y":-0.1448974609375},{"x":-0.3980865478515625,"y":-0.14276123046875},{"x":-0.3089141845703125,"y":-0.00677490234375},{"x":-0.5052642822265625,"y":0.143035888671875},{"x":-0.10577392578125,"y":0.212310791015625},{"x":-0.235321044921875,"y":-0.127593994140625},{"x":0.376556396484375,"y":-0.29608154296875},{"x":-0.428863525390625,"y":0.04693603515625},{"x":-0.2655487060546875,"y":0.13299560546875},{"x":0.0776214599609375,"y":-0.11956787109375},{"x":-0.2388458251953125,"y":-0.06494140625},{"x":0.034515380859375,"y":-0.016876220703125},{"x":0.40740966796875,"y":0.326904296875},{"x":0.40643310546875,"y":-0.11810302734375}],"optimisedCameraToObject":{"translation":{"x":-0.19093928670759655,"y":-0.06030370969747975,"z":0.47843488448395616},"rotation":{"quaternion":{"W":0.9905543918397711,"X":0.07821383582808601,"Y":0.10244881080613036,"Z":0.046784974686410845}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":190.16746520996094,"y":143.6483612060547},{"x":232.9264373779297,"y":146.91757202148438},{"x":274.3643798828125,"y":150.08258056640625},{"x":314.30096435546875,"y":153.482177734375},{"x":352.54217529296875,"y":156.5852508544922},{"x":390.0780944824219,"y":159.57150268554688},{"x":425.94189453125,"y":162.14874267578125},{"x":189.255126953125,"y":185.86090087890625},{"x":232.15676879882812,"y":188.27972412109375},{"x":272.73980712890625,"y":190.87521362304688},{"x":312.7359313964844,"y":193.68670654296875},{"x":351.0829162597656,"y":196.02769470214844},{"x":388.3519287109375,"y":198.09368896484375},{"x":423.9833984375,"y":200.28611755371094},{"x":188.35340881347656,"y":227.68710327148438},{"x":230.62713623046875,"y":229.65335083007812},{"x":271.5768737792969,"y":231.12295532226562},{"x":311.01300048828125,"y":233.15292358398438},{"x":349.0953063964844,"y":235.00526428222656},{"x":386.16455078125,"y":236.61349487304688},{"x":421.8720397949219,"y":238.08103942871094},{"x":187.4383087158203,"y":269.0171813964844},{"x":229.74769592285156,"y":270.00946044921875},{"x":269.96893310546875,"y":271.0544738769531},{"x":309.5205993652344,"y":272.68438720703125},{"x":347.4969177246094,"y":273.46392822265625},{"x":384.5373840332031,"y":274.8607177734375},{"x":419.8016357421875,"y":275.8512268066406},{"x":186.5628204345703,"y":309.2423095703125},{"x":228.2252655029297,"y":309.78009033203125},{"x":268.69036865234375,"y":310.25726318359375},{"x":307.8885803222656,"y":310.7570495605469},{"x":345.8280029296875,"y":311.1353759765625},{"x":382.39013671875,"y":311.9581298828125},{"x":418.0929260253906,"y":312.3589172363281},{"x":185.26693725585938,"y":349.5543518066406},{"x":227.11549377441406,"y":349.55419921875},{"x":266.98382568359375,"y":349.2853088378906},{"x":306.2809753417969,"y":349.4573974609375},{"x":343.7716064453125,"y":349.3941650390625},{"x":380.6850891113281,"y":349.2898864746094},{"x":415.9270324707031,"y":349.35089111328125},{"x":184.5811004638672,"y":389.0827331542969},{"x":225.88528442382812,"y":388.6552734375},{"x":266.0425720214844,"y":387.9825439453125},{"x":304.8479919433594,"y":387.1640930175781},{"x":342.18994140625,"y":386.4454040527344},{"x":378.5357971191406,"y":385.92352294921875},{"x":413.9472961425781,"y":385.5028991699219}],"reprojectionErrors":[{"x":0.408355712890625,"y":-0.083587646484375},{"x":0.14666748046875,"y":-0.0677337646484375},{"x":-0.136199951171875,"y":-0.045440673828125},{"x":-0.207275390625,"y":-0.3517303466796875},{"x":0.177520751953125,"y":-0.4518585205078125},{"x":0.07568359375,"y":-0.522125244140625},{"x":0.499359130859375,"y":-0.2670745849609375},{"x":0.388580322265625,"y":-0.07440185546875},{"x":-0.2545623779296875,"y":0.102630615234375},{"x":0.094146728515625,"y":0.024017333984375},{"x":-0.245330810546875,"y":-0.346527099609375},{"x":-0.16156005859375,"y":-0.319580078125},{"x":-0.178985595703125,"y":-0.0879058837890625},{"x":0.30645751953125,"y":-0.0502777099609375},{"x":0.3690948486328125,"y":-0.1883392333984375},{"x":0.11553955078125,"y":-0.2318267822265625},{"x":-0.125457763671875,"y":0.1604461669921875},{"x":-0.113525390625,"y":-0.0661468505859375},{"x":0.039764404296875,"y":-0.17138671875},{"x":0.03961181640625,"y":-0.0866546630859375},{"x":0.2784423828125,"y":0.086669921875},{"x":0.3738250732421875,"y":-0.313018798828125},{"x":-0.1532135009765625,"y":-0.03973388671875},{"x":0.111663818359375,"y":0.137359619140625},{"x":-0.200347900390625,"y":-0.312164306640625},{"x":-0.13604736328125,"y":0.048553466796875},{"x":-0.28985595703125,"y":-0.24652099609375},{"x":0.221588134765625,"y":-0.172454833984375},{"x":0.3497467041015625,"y":0.163177490234375},{"x":0.2323455810546875,"y":0.249359130859375},{"x":0.031097412109375,"y":0.36956787109375},{"x":-0.13555908203125,"y":0.441558837890625},{"x":-0.22918701171875,"y":0.610504150390625},{"x":-0.087005615234375,"y":0.311431884765625},{"x":-0.184722900390625,"y":0.411712646484375},{"x":0.7567901611328125,"y":0.05108642578125},{"x":0.216522216796875,"y":0.049102783203125},{"x":0.390228271484375,"y":0.305419921875},{"x":-0.083160400390625,"y":0.110748291015625},{"x":0.077362060546875,"y":0.141845703125},{"x":-0.314056396484375,"y":0.204925537109375},{"x":-0.121551513671875,"y":0.093994140625},{"x":0.564483642578125,"y":0.224273681640625},{"x":0.3323974609375,"y":0.038665771484375},{"x":-0.004241943359375,"y":0.10345458984375},{"x":-0.193389892578125,"y":0.318939208984375},{"x":-0.078582763671875,"y":0.439605712890625},{"x":-0.084503173828125,"y":0.3682861328125},{"x":-0.232086181640625,"y":0.200469970703125}],"optimisedCameraToObject":{"translation":{"x":-0.13350220864243958,"y":-0.11844978960616115,"z":0.40735206253438333},"rotation":{"quaternion":{"W":0.9892457239984286,"X":0.05386148376378119,"Y":-0.13483600756999845,"Z":0.01763772037911974}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":135.70372009277344,"y":130.54415893554688},{"x":171.04296875,"y":133.48390197753906},{"x":204.86813354492188,"y":136.50344848632812},{"x":236.7733917236328,"y":139.4121551513672},{"x":267.80328369140625,"y":142.12548828125},{"x":297.23724365234375,"y":145.0078582763672},{"x":325.42840576171875,"y":147.2733154296875},{"x":135.77622985839844,"y":164.85025024414062},{"x":170.9188690185547,"y":167.14198303222656},{"x":204.05380249023438,"y":169.6541290283203},{"x":236.2957000732422,"y":171.9164276123047},{"x":266.98126220703125,"y":173.62393188476562},{"x":296.63201904296875,"y":175.88377380371094},{"x":324.6925048828125,"y":177.76669311523438},{"x":135.8569793701172,"y":199.04226684570312},{"x":170.4993438720703,"y":200.33941650390625},{"x":203.87008666992188,"y":201.97802734375},{"x":235.69801330566406,"y":203.43576049804688},{"x":266.0592956542969,"y":205.0555419921875},{"x":295.6465148925781,"y":206.41632080078125},{"x":323.4291076660156,"y":207.39642333984375},{"x":135.67372131347656,"y":232.6307830810547},{"x":170.05120849609375,"y":233.51934814453125},{"x":203.15731811523438,"y":234.11045837402344},{"x":235.13768005371094,"y":234.9561004638672},{"x":265.3049621582031,"y":235.984375},{"x":294.562255859375,"y":236.436767578125},{"x":322.2104797363281,"y":237.13143920898438},{"x":135.68780517578125,"y":265.1072082519531},{"x":169.90780639648438,"y":265.2215270996094},{"x":202.70770263671875,"y":265.6954650878906},{"x":234.25071716308594,"y":265.9800720214844},{"x":264.36181640625,"y":266.0235290527344},{"x":291.53448486328125,"y":265.2059631347656},{"x":321.4366149902344,"y":266.0709533691406},{"x":135.32705688476562,"y":298.01507568359375},{"x":169.63197326660156,"y":297.583740234375},{"x":202.10183715820312,"y":297.10906982421875},{"x":233.39935302734375,"y":296.8614807128906},{"x":263.5686950683594,"y":296.10162353515625},{"x":292.72344970703125,"y":295.94256591796875},{"x":320.4378662109375,"y":295.2640380859375},{"x":135.24295043945312,"y":330.0309753417969},{"x":169.0897216796875,"y":329.0679016113281},{"x":201.6971435546875,"y":328.0373229980469},{"x":232.90109252929688,"y":326.9543762207031},{"x":262.87213134765625,"y":325.78521728515625},{"x":291.6903381347656,"y":324.8067321777344},{"x":319.0472412109375,"y":324.0692138671875}],"reprojectionErrors":[{"x":0.6999969482421875,"y":0.1876068115234375},{"x":0.1791534423828125,"y":0.187469482421875},{"x":-0.2088775634765625,"y":-0.00518798828125},{"x":0.016021728515625,"y":-0.193695068359375},{"x":-0.12158203125,"y":-0.2878875732421875},{"x":0.16314697265625,"y":-0.6469573974609375},{"x":0.577117919921875,"y":-0.48004150390625},{"x":0.544830322265625,"y":0.2069549560546875},{"x":4.57763671875E-4,"y":0.1505889892578125},{"x":0.099822998046875,"y":-0.212646484375},{"x":-0.19891357421875,"y":-0.4078826904296875},{"x":-0.16461181640625,"y":-0.1258544921875},{"x":-0.25567626953125,"y":-0.4697265625},{"x":0.142333984375,"y":-0.5064849853515625},{"x":0.37921142578125,"y":-0.1033935546875},{"x":0.116455078125,"y":0.148223876953125},{"x":-0.2216033935546875,"y":-0.002777099609375},{"x":-0.29229736328125,"y":-0.030792236328125},{"x":-0.105255126953125,"y":-0.2757568359375},{"x":-0.291046142578125,"y":-0.31378173828125},{"x":0.23883056640625,"y":-0.02056884765625},{"x":0.4754180908203125,"y":-0.24951171875},{"x":0.2603607177734375,"y":-0.258575439453125},{"x":-0.0134124755859375,"y":-0.0070037841796875},{"x":-0.421417236328125,"y":-0.0448455810546875},{"x":-0.21099853515625,"y":-0.2983551025390625},{"x":-0.224365234375,"y":-0.007354736328125},{"x":0.29443359375,"y":0.0116119384765625},{"x":0.3721771240234375,"y":0.28173828125},{"x":0.098876953125,"y":0.394622802734375},{"x":-0.067779541015625,"y":0.134490966796875},{"x":-0.2222442626953125,"y":0.05096435546875},{"x":-0.125396728515625,"y":0.19659423828125},{"x":1.789093017578125,"y":1.19183349609375},{"x":-0.0908203125,"y":0.49371337890625},{"x":0.641693115234375,"y":-0.0487060546875},{"x":0.0692291259765625,"y":-0.02581787109375},{"x":0.034759521484375,"y":0.04949951171875},{"x":-0.0569610595703125,"y":-0.0936279296875},{"x":-0.18719482421875,"y":0.283721923828125},{"x":-0.410797119140625,"y":0.068145751953125},{"x":-0.2471923828125,"y":0.3795166015625},{"x":0.632568359375,"y":0.087066650390625},{"x":0.3054351806640625,"y":0.022369384765625},{"x":-0.0631866455078125,"y":0.055877685546875},{"x":-0.2430267333984375,"y":0.1708984375},{"x":-0.3428955078125,"y":0.399871826171875},{"x":-0.385223388671875,"y":0.46453857421875},{"x":-0.00762939453125,"y":0.3133544921875}],"optimisedCameraToObject":{"translation":{"x":-0.19899474827153943,"y":-0.14911436496015743,"z":0.5013172545504098},"rotation":{"quaternion":{"W":0.9741621681960915,"X":0.07103489358595931,"Y":-0.21417932030088419,"Z":0.009451597969270916}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":145.9443817138672,"y":304.1503601074219},{"x":186.30406188964844,"y":306.0598449707031},{"x":225.12879943847656,"y":307.8197021484375},{"x":264.03631591796875,"y":309.304931640625},{"x":301.690185546875,"y":311.07177734375},{"x":339.0354309082031,"y":312.703369140625},{"x":375.21649169921875,"y":314.0296630859375},{"x":145.766845703125,"y":340.86181640625},{"x":185.43724060058594,"y":342.3179626464844},{"x":223.99205017089844,"y":343.4752502441406},{"x":262.1709899902344,"y":345.4200439453125},{"x":299.7766418457031,"y":346.61285400390625},{"x":336.4263916015625,"y":347.7964172363281},{"x":371.9783935546875,"y":348.98626708984375},{"x":145.46630859375,"y":376.8085632324219},{"x":184.12835693359375,"y":377.4175720214844},{"x":222.9355010986328,"y":378.9134216308594},{"x":260.31829833984375,"y":379.8584899902344},{"x":297.1507263183594,"y":380.88885498046875},{"x":333.5131530761719,"y":382.0174560546875},{"x":368.8775939941406,"y":383.1126403808594},{"x":145.17442321777344,"y":411.5334777832031},{"x":183.7990264892578,"y":412.43768310546875},{"x":221.43624877929688,"y":413.2135009765625},{"x":258.7510070800781,"y":413.92462158203125},{"x":294.6881408691406,"y":414.283447265625},{"x":330.9254150390625,"y":415.66522216796875},{"x":366.0765075683594,"y":416.2132873535156},{"x":145.04808044433594,"y":445.2568359375},{"x":182.96188354492188,"y":445.8124084472656},{"x":220.13418579101562,"y":446.3155212402344},{"x":257.0215759277344,"y":446.68756103515625},{"x":293.0394592285156,"y":447.15338134765625},{"x":328.2884826660156,"y":447.6198425292969},{"x":363.2686462402344,"y":448.06353759765625},{"x":144.3304443359375,"y":478.4935607910156},{"x":182.11508178710938,"y":478.9269714355469},{"x":218.7119903564453,"y":479.105224609375},{"x":255.25474548339844,"y":479.22821044921875},{"x":290.97125244140625,"y":479.6271667480469},{"x":325.8437805175781,"y":480.07696533203125},{"x":360.1378173828125,"y":480.35833740234375},{"x":144.4270782470703,"y":510.79913330078125},{"x":181.16558837890625,"y":510.7248229980469},{"x":217.770263671875,"y":511.0228271484375},{"x":253.59451293945312,"y":510.9925231933594},{"x":288.8172607421875,"y":511.0450744628906},{"x":323.54339599609375,"y":510.8504943847656},{"x":357.57879638671875,"y":511.0558776855469}],"reprojectionErrors":[{"x":0.0764617919921875,"y":-0.255523681640625},{"x":-0.305877685546875,"y":-0.317657470703125},{"x":0.148162841796875,"y":-0.277587890625},{"x":-0.169677734375,"y":-0.009521484375},{"x":0.086456298828125,"y":-0.06884765625},{"x":-0.019073486328125,"y":-0.03790283203125},{"x":0.378631591796875,"y":0.25421142578125},{"x":-0.0164794921875,"y":-0.03033447265625},{"x":-0.249847412109375,"y":0.01312255859375},{"x":-0.047332763671875,"y":0.311859130859375},{"x":-0.139678955078125,"y":-0.2196044921875},{"x":-0.320556640625,"y":-0.041015625},{"x":-0.19842529296875,"y":0.10565185546875},{"x":0.37744140625,"y":0.205657958984375},{"x":0.0269317626953125,"y":-0.051300048828125},{"x":0.2740631103515625,"y":0.50946044921875},{"x":-0.2854156494140625,"y":0.1434326171875},{"x":-0.073577880859375,"y":0.289031982421875},{"x":0.0440673828125,"y":0.310882568359375},{"x":-0.004425048828125,"y":0.196868896484375},{"x":0.31744384765625,"y":0.079345703125},{"x":0.0745391845703125,"y":0.174102783203125},{"x":-0.1566619873046875,"y":0.126861572265625},{"x":-0.044464111328125,"y":0.17132568359375},{"x":-0.245758056640625,"y":0.24456787109375},{"x":0.302642822265625,"y":0.634918212890625},{"x":-0.06903076171875,"y":-0.03216552734375},{"x":0.03363037109375,"y":0.10076904296875},{"x":-0.031036376953125,"y":0.4593505859375},{"x":-0.0555419921875,"y":0.464019775390625},{"x":0.0343780517578125,"y":0.48748779296875},{"x":-0.210296630859375,"y":0.609039306640625},{"x":-0.197296142578125,"y":0.604583740234375},{"x":-0.01971435546875,"y":0.567962646484375},{"x":-0.169891357421875,"y":0.52325439453125},{"x":0.4665985107421875,"y":0.32183837890625},{"x":0.0784454345703125,"y":0.167205810546875},{"x":0.267242431640625,"y":0.23675537109375},{"x":-0.093414306640625,"y":0.331329345703125},{"x":-0.224151611328125,"y":0.120391845703125},{"x":-0.10003662109375,"y":-0.17022705078125},{"x":0.02069091796875,"y":-0.32061767578125},{"x":0.1614532470703125,"y":0.236968994140625},{"x":0.3375244140625,"y":0.322998046875},{"x":0.0523834228515625,"y":0.008270263671875},{"x":-0.0405731201171875,"y":-0.005950927734375},{"x":-0.113372802734375,"y":-0.130126953125},{"x":-0.26409912109375,"y":-0.0335693359375},{"x":-0.291656494140625,"y":-0.36273193359375}],"optimisedCameraToObject":{"translation":{"x":-0.17046697055025048,"y":-0.020720616241335747,"z":0.4376303191485832},"rotation":{"quaternion":{"W":0.988276934138473,"X":0.12741949596490243,"Y":-0.07662921800871669,"Z":0.0346545299388587}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img15.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.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.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":238.13990783691406,"y":137.11822509765625},{"x":275.8232116699219,"y":140.14871215820312},{"x":313.0944519042969,"y":143.5035858154297},{"x":349.5731506347656,"y":146.15182495117188},{"x":385.9819641113281,"y":149.22865295410156},{"x":198.546875,"y":172.1566925048828},{"x":310.92333984375,"y":180.662353515625},{"x":347.7194519042969,"y":183.1135711669922},{"x":383.3493957519531,"y":185.72036743164062},{"x":158.65052795410156,"y":206.96470642089844},{"x":196.72593688964844,"y":209.5020751953125},{"x":345.0337829589844,"y":219.84605407714844},{"x":380.94268798828125,"y":222.14138793945312},{"x":157.2664031982422,"y":244.6553192138672},{"x":195.4091033935547,"y":246.92889404296875},{"x":232.61843872070312,"y":249.07127380371094},{"x":343.0581970214844,"y":255.92236328125},{"x":378.44793701171875,"y":258.24664306640625},{"x":155.88987731933594,"y":281.3567199707031},{"x":193.85877990722656,"y":283.3215026855469},{"x":230.8083038330078,"y":285.7000732421875},{"x":268.09149169921875,"y":287.6693420410156},{"x":304.64190673828125,"y":289.7224426269531},{"x":340.5041198730469,"y":291.5997619628906},{"x":376.1053771972656,"y":293.8971252441406},{"x":154.47230529785156,"y":318.2977600097656},{"x":192.2004852294922,"y":320.0201416015625},{"x":229.2196807861328,"y":321.9282531738281},{"x":266.19097900390625,"y":323.9358215332031},{"x":302.3787536621094,"y":325.3965759277344},{"x":338.40753173828125,"y":327.6666564941406},{"x":190.65594482421875,"y":356.0038757324219},{"x":227.5541534423828,"y":357.852783203125},{"x":264.1708679199219,"y":359.1638488769531},{"x":300.3353271484375,"y":361.03277587890625},{"x":336.1874694824219,"y":362.30023193359375}],"reprojectionErrors":[{"x":0.0576171875,"y":-0.137176513671875},{"x":0.024505615234375,"y":-0.07781982421875},{"x":-0.08294677734375,"y":-0.37640380859375},{"x":0.11663818359375,"y":-0.001922607421875},{"x":-0.098175048828125,"y":-0.0896759033203125},{"x":-0.1067352294921875,"y":-0.2735748291015625},{"x":-0.0682373046875,"y":-0.2872161865234375},{"x":-0.3551025390625,"y":0.026458740234375},{"x":0.044647216796875,"y":0.15167236328125},{"x":-0.056610107421875,"y":-0.0841827392578125},{"x":0.115509033203125,"y":0.0195465087890625},{"x":0.02569580078125,"y":-0.0831451416015625},{"x":-0.01800537109375,"y":0.1012725830078125},{"x":-0.0610504150390625,"y":-0.2724456787109375},{"x":-0.1451568603515625,"y":-0.1552886962890625},{"x":0.231292724609375,"y":0.0612335205078125},{"x":-0.282958984375,"y":0.096405029296875},{"x":0.02783203125,"y":0.00439453125},{"x":-0.05194091796875,"y":0.137542724609375},{"x":-0.1512451171875,"y":0.318084716796875},{"x":0.30096435546875,"y":0.053436279296875},{"x":-0.048004150390625,"y":0.166778564453125},{"x":-0.131195068359375,"y":0.165130615234375},{"x":0.007537841796875,"y":0.308197021484375},{"x":-0.05810546875,"y":3.662109375E-4},{"x":0.0192108154296875,"y":-0.0823974609375},{"x":-0.0283660888671875,"y":0.100006103515625},{"x":0.170074462890625,"y":0.065643310546875},{"x":-0.0462646484375,"y":-0.098968505859375},{"x":0.0587158203125,"y":0.252532958984375},{"x":-0.138824462890625,"y":-0.23577880859375},{"x":0.0016632080078125,"y":0.212066650390625},{"x":0.1369781494140625,"y":0.0015869140625},{"x":0.095916748046875,"y":0.298553466796875},{"x":0.0496826171875,"y":0.0074462890625},{"x":-0.14105224609375,"y":0.287811279296875}],"optimisedCameraToObject":{"translation":{"x":-0.16474605442443782,"y":-0.13756812250190248,"z":0.45451932807657547},"rotation":{"quaternion":{"W":0.9965723249910379,"X":0.04979101897245024,"Y":-0.058486485323024306,"Z":0.03072110880489241}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":160.26551818847656,"y":272.7175598144531},{"x":195.88360595703125,"y":275.1936340332031},{"x":231.47735595703125,"y":277.8559875488281},{"x":267.0601806640625,"y":280.1815185546875},{"x":301.7333068847656,"y":282.92889404296875},{"x":336.9476013183594,"y":285.23065185546875},{"x":371.40838623046875,"y":288.21868896484375},{"x":159.40530395507812,"y":307.0029296875},{"x":195.26065063476562,"y":309.3342590332031},{"x":230.195556640625,"y":312.2760314941406},{"x":265.2735290527344,"y":314.5755310058594},{"x":299.4888610839844,"y":316.6572265625},{"x":334.62982177734375,"y":319.2293395996094},{"x":368.6734313964844,"y":321.7421875},{"x":159.04246520996094,"y":340.8913879394531},{"x":193.65792846679688,"y":342.9244384765625},{"x":228.91427612304688,"y":345.376953125},{"x":263.43255615234375,"y":347.7806396484375},{"x":297.80975341796875,"y":350.1204833984375},{"x":332.1525573730469,"y":352.4575500488281},{"x":365.96124267578125,"y":355.0853271484375},{"x":158.5865478515625,"y":374.194580078125},{"x":193.12576293945312,"y":376.2279968261719},{"x":227.3429718017578,"y":378.2856140136719},{"x":261.91351318359375,"y":380.769287109375},{"x":295.6500549316406,"y":382.97076416015625},{"x":329.76055908203125,"y":385.4019775390625},{"x":363.3720703125,"y":387.3465270996094},{"x":157.8304901123047,"y":406.03533935546875},{"x":192.0241241455078,"y":408.03607177734375},{"x":226.2036590576172,"y":410.28558349609375},{"x":260.2247009277344,"y":412.803955078125},{"x":293.8889465332031,"y":414.9324645996094},{"x":327.67071533203125,"y":416.85906982421875},{"x":361.02801513671875,"y":419.10198974609375},{"x":156.90638732910156,"y":437.9564514160156},{"x":191.2289581298828,"y":440.166015625},{"x":224.82415771484375,"y":442.2236022949219},{"x":258.4577941894531,"y":444.5066833496094},{"x":291.90069580078125,"y":446.6847839355469},{"x":324.962646484375,"y":449.098876953125},{"x":358.1766662597656,"y":450.8293151855469},{"x":156.5986785888672,"y":469.13006591796875},{"x":190.12892150878906,"y":471.2291259765625},{"x":223.61407470703125,"y":473.41015625},{"x":256.6712951660156,"y":475.2705383300781},{"x":289.9999084472656,"y":477.67413330078125},{"x":323.01513671875,"y":479.81353759765625},{"x":355.99945068359375,"y":481.8311462402344}],"reprojectionErrors":[{"x":0.131683349609375,"y":-0.2236328125},{"x":0.08544921875,"y":-0.06707763671875},{"x":-0.07623291015625,"y":-0.11651611328125},{"x":-0.373565673828125,"y":0.15069580078125},{"x":0.085601806640625,"y":-0.0245361328125},{"x":-0.1561279296875,"y":0.224853515625},{"x":0.189483642578125,"y":-0.23345947265625},{"x":0.2985687255859375,"y":-0.036376953125},{"x":-0.335235595703125,"y":0.167510986328125},{"x":-0.1854705810546875,"y":-0.260650634765625},{"x":-0.322265625,"y":-0.06854248046875},{"x":0.253509521484375,"y":0.319000244140625},{"x":-0.2528076171875,"y":0.193389892578125},{"x":0.17547607421875,"y":0.103912353515625},{"x":-0.009490966796875,"y":-0.137054443359375},{"x":0.251495361328125,"y":0.2708740234375},{"x":-0.262420654296875,"y":0.235931396484375},{"x":-0.178802490234375,"y":0.226104736328125},{"x":-0.10107421875,"y":0.256011962890625},{"x":-0.1422119140625,"y":0.264251708984375},{"x":0.19134521484375,"y":-0.04296875},{"x":-0.202606201171875,"y":-0.321868896484375},{"x":-0.2053680419921875,"y":-0.0054931640625},{"x":-0.017333984375,"y":0.261627197265625},{"x":-0.320281982421875,"y":0.077239990234375},{"x":0.06683349609375,"y":0.149322509765625},{"x":-0.0701904296875,"y":-0.034393310546875},{"x":0.1356201171875,"y":0.242218017578125},{"x":-0.07427978515625,"y":0.3013916015625},{"x":-0.0664215087890625,"y":0.562286376953125},{"x":-0.1729583740234375,"y":0.547698974609375},{"x":-0.255828857421875,"y":0.2371826171875},{"x":-0.1229248046875,"y":0.289215087890625},{"x":-0.254638671875,"y":0.515533447265625},{"x":-0.11492919921875,"y":0.397674560546875},{"x":0.24285888671875,"y":0.204559326171875},{"x":-0.208251953125,"y":0.171356201171875},{"x":-0.057861328125,"y":0.261810302734375},{"x":-0.077972412109375,"y":0.098175048828125},{"x":-0.045501708984375,"y":0.010650634765625},{"x":0.22381591796875,"y":-0.34197998046875},{"x":0.1910400390625,"y":-0.040252685546875},{"x":-0.0361328125,"y":0.22979736328125},{"x":-0.0201416015625,"y":0.224578857421875},{"x":-0.08233642578125,"y":0.1075439453125},{"x":0.15399169921875,"y":0.281097412109375},{"x":-0.016387939453125,"y":-0.118927001953125},{"x":-0.0146484375,"y":-0.2852783203125},{"x":-0.128997802734375,"y":-0.36053466796875}],"optimisedCameraToObject":{"translation":{"x":-0.1753115920804864,"y":-0.043666000458725415,"z":0.48654877691340925},"rotation":{"quaternion":{"W":0.9941663820482253,"X":0.09919308416060063,"Y":-0.018036637810928277,"Z":0.038322533271270824}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":237.299072265625,"y":286.8665466308594},{"x":272.99066162109375,"y":288.5672302246094},{"x":308.3810729980469,"y":291.0510559082031},{"x":343.4644775390625,"y":292.853271484375},{"x":378.30926513671875,"y":294.9846496582031},{"x":412.9327697753906,"y":297.1768493652344},{"x":446.91314697265625,"y":299.0771789550781},{"x":236.1217041015625,"y":320.85430908203125},{"x":271.66583251953125,"y":322.9089050292969},{"x":306.41009521484375,"y":324.9311828613281},{"x":341.43743896484375,"y":326.9419860839844},{"x":375.86285400390625,"y":328.8192138671875},{"x":410.0010681152344,"y":330.8968200683594},{"x":443.73968505859375,"y":332.1127624511719},{"x":235.51800537109375,"y":354.6820068359375},{"x":270.1289367675781,"y":356.13787841796875},{"x":304.99749755859375,"y":358.0947570800781},{"x":339.22900390625,"y":359.9287414550781},{"x":372.9646301269531,"y":362.022216796875},{"x":407.3037109375,"y":363.8982238769531},{"x":440.774658203125,"y":365.3619079589844},{"x":234.11082458496094,"y":387.47430419921875},{"x":268.93536376953125,"y":389.2257080078125},{"x":302.982421875,"y":391.10528564453125},{"x":337.22760009765625,"y":392.86090087890625},{"x":370.87017822265625,"y":394.6519775390625},{"x":404.6983642578125,"y":396.0712890625},{"x":437.72119140625,"y":397.9093017578125},{"x":233.04754638671875,"y":419.73846435546875},{"x":267.0989990234375,"y":421.1092529296875},{"x":301.0884094238281,"y":422.9915771484375},{"x":335.1882629394531,"y":424.4372253417969},{"x":368.6764831542969,"y":425.9659729003906},{"x":401.8834228515625,"y":427.7222595214844},{"x":434.8236999511719,"y":429.194091796875},{"x":231.87452697753906,"y":451.18218994140625},{"x":266.0405578613281,"y":452.9459533691406},{"x":299.6012268066406,"y":454.3401184082031},{"x":333.06744384765625,"y":456.0312805175781},{"x":366.0672607421875,"y":457.38043212890625},{"x":399.13494873046875,"y":459.18988037109375},{"x":431.918701171875,"y":460.85809326171875},{"x":230.88746643066406,"y":482.38348388671875},{"x":264.423583984375,"y":483.84490966796875},{"x":297.7781066894531,"y":485.5733947753906},{"x":331.1012268066406,"y":486.8656005859375},{"x":363.9580078125,"y":488.1300048828125},{"x":396.6248779296875,"y":489.7809143066406},{"x":428.95220947265625,"y":491.3472595214844}],"reprojectionErrors":[{"x":0.2255096435546875,"y":-0.311431884765625},{"x":0.038177490234375,"y":0.144622802734375},{"x":-0.06170654296875,"y":-0.205352783203125},{"x":-0.074005126953125,"y":0.103118896484375},{"x":-0.072479248046875,"y":0.059051513671875},{"x":-0.079864501953125,"y":-0.0694580078125},{"x":0.32061767578125,"y":0.070098876953125},{"x":0.26556396484375,"y":0.04718017578125},{"x":-0.124298095703125,"y":0.024169921875},{"x":0.0762939453125,"y":0.009124755859375},{"x":-0.22113037109375,"y":-0.019012451171875},{"x":-0.13690185546875,"y":0.0616455078125},{"x":0.00897216796875,"y":-0.082977294921875},{"x":0.3238525390625,"y":0.60894775390625},{"x":-0.2408905029296875,"y":-0.122344970703125},{"x":-0.042327880859375,"y":0.3326416015625},{"x":-0.306549072265625,"y":0.2608642578125},{"x":-0.144317626953125,"y":0.28607177734375},{"x":0.29791259765625,"y":0.025665283203125},{"x":-0.0843505859375,"y":-0.04345703125},{"x":0.175506591796875,"y":0.27337646484375},{"x":0.0826263427734375,"y":0.071075439453125},{"x":-0.272064208984375,"y":0.11407470703125},{"x":-0.050262451171875,"y":0.001800537109375},{"x":-0.23297119140625,"y":-0.013763427734375},{"x":-0.024658203125,"y":-0.092132568359375},{"x":-0.218597412109375,"y":0.173797607421875},{"x":0.1712646484375,"y":-0.006500244140625},{"x":0.0881195068359375,"y":0.135467529296875},{"x":0.171905517578125,"y":0.44677734375},{"x":0.120758056640625,"y":0.2181396484375},{"x":-0.243072509765625,"y":0.39764404296875},{"x":-0.20263671875,"y":0.4654541015625},{"x":-0.093292236328125,"y":0.277099609375},{"x":0.065521240234375,"y":0.344451904296875},{"x":0.228607177734375,"y":0.3780517578125},{"x":-0.131866455078125,"y":0.188018798828125},{"x":-0.08001708984375,"y":0.337921142578125},{"x":-0.131927490234375,"y":0.161102294921875},{"x":0.07928466796875,"y":0.296478271484375},{"x":0.014434814453125,"y":-0.0582275390625},{"x":0.020538330078125,"y":-0.301544189453125},{"x":0.2077789306640625,"y":0.235260009765625},{"x":0.152374267578125,"y":0.243072509765625},{"x":0.08935546875,"y":-0.047088623046875},{"x":-0.136566162109375,"y":0.068115234375},{"x":-0.09539794921875,"y":0.180206298828125},{"x":-0.068450927734375,"y":-0.125152587890625},{"x":0.0892333984375,"y":-0.3768310546875}],"optimisedCameraToObject":{"translation":{"x":-0.120077643813806,"y":-0.03325096713216061,"z":0.4860159725300603},"rotation":{"quaternion":{"W":0.9940334673230898,"X":0.10018342340729534,"Y":-0.027929824547626648,"Z":0.03287358235375339}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":237.25791931152344,"y":292.55426025390625},{"x":272.83160400390625,"y":294.8651428222656},{"x":308.0140380859375,"y":297.2074890136719},{"x":342.9413757324219,"y":299.2397766113281},{"x":377.3575134277344,"y":301.60601806640625},{"x":411.9292297363281,"y":303.8905944824219},{"x":445.7149658203125,"y":306.2012939453125},{"x":236.04196166992188,"y":326.6026306152344},{"x":271.2687072753906,"y":328.7168884277344},{"x":305.80303955078125,"y":330.8786315917969},{"x":340.4033508300781,"y":333.1482849121094},{"x":374.52203369140625,"y":334.95758056640625},{"x":408.93145751953125,"y":337.1377868652344},{"x":442.4022521972656,"y":338.9502868652344},{"x":235.01246643066406,"y":359.7694396972656},{"x":269.40533447265625,"y":361.5374450683594},{"x":304.013427734375,"y":363.8246154785156},{"x":338.03887939453125,"y":365.481689453125},{"x":371.95758056640625,"y":367.8439025878906},{"x":406.0009765625,"y":369.9101257324219},{"x":439.2597351074219,"y":371.49945068359375},{"x":233.6402587890625,"y":392.2527160644531},{"x":267.9810791015625,"y":394.38983154296875},{"x":302.01806640625,"y":396.0508117675781},{"x":335.9541320800781,"y":398.1384582519531},{"x":369.4820556640625,"y":400.0735168457031},{"x":403.0712585449219,"y":401.8822937011719},{"x":435.952880859375,"y":403.8533020019531},{"x":232.5345916748047,"y":423.9532470703125},{"x":266.5255432128906,"y":425.7818908691406},{"x":300.1537780761719,"y":427.8794860839844},{"x":333.7389831542969,"y":429.27215576171875},{"x":366.9523620605469,"y":431.1911926269531},{"x":400.0719299316406,"y":432.8009948730469},{"x":432.878173828125,"y":434.66796875},{"x":231.15626525878906,"y":455.4431457519531},{"x":264.9363098144531,"y":457.0746765136719},{"x":298.2123718261719,"y":458.881591796875},{"x":331.6088562011719,"y":460.1883850097656},{"x":364.2332763671875,"y":462.11016845703125},{"x":397.2676086425781,"y":464.05950927734375},{"x":429.5316467285156,"y":465.2807312011719},{"x":230.10865783691406,"y":485.9787292480469},{"x":263.2046813964844,"y":487.3025207519531},{"x":296.48486328125,"y":489.2945861816406},{"x":329.3624267578125,"y":490.7539978027344},{"x":361.9385986328125,"y":492.32037353515625},{"x":394.4825439453125,"y":493.9151916503906},{"x":426.77606201171875,"y":495.8111572265625}],"reprojectionErrors":[{"x":0.129974365234375,"y":-0.0556640625},{"x":-0.1085205078125,"y":-0.037689208984375},{"x":-0.170196533203125,"y":-0.076263427734375},{"x":-0.19677734375,"y":0.169830322265625},{"x":0.06256103515625,"y":0.056365966796875},{"x":-0.064178466796875,"y":-0.00128173828125},{"x":0.359527587890625,"y":-0.111114501953125},{"x":0.0801849365234375,"y":-0.093902587890625},{"x":-0.17950439453125,"y":-0.007293701171875},{"x":0.04339599609375,"y":0.005401611328125},{"x":-0.014923095703125,"y":-0.116546630859375},{"x":0.1878662109375,"y":0.19500732421875},{"x":-0.125701904296875,"y":0.10858154296875},{"x":0.268829345703125,"y":0.36260986328125},{"x":-0.12493896484375,"y":0.029022216796875},{"x":0.087127685546875,"y":0.338623046875},{"x":-0.121337890625,"y":0.101318359375},{"x":0.042144775390625,"y":0.466156005859375},{"x":0.096588134765625,"y":0.097747802734375},{"x":-0.194549560546875,"y":-0.0029296875},{"x":0.0732421875,"y":0.344940185546875},{"x":0.0429840087890625,"y":0.13299560546875},{"x":-0.04913330078125,"y":-0.045196533203125},{"x":-0.03839111328125,"y":0.2237548828125},{"x":-0.13287353515625,"y":0.036834716796875},{"x":-0.030517578125,"y":-0.0267333984375},{"x":-0.2056884765625,"y":0.006561279296875},{"x":0.105712890625,"y":-0.151885986328125},{"x":-0.0260772705078125,"y":0.334716796875},{"x":-0.11883544921875,"y":0.350677490234375},{"x":-0.0455322265625,"y":0.067474365234375},{"x":-0.131072998046875,"y":0.4588623046875},{"x":-0.0516357421875,"y":0.293487548828125},{"x":-0.090087890625,"y":0.406829833984375},{"x":-0.03167724609375,"y":0.232452392578125},{"x":0.2063140869140625,"y":0.078887939453125},{"x":-0.0203857421875,"y":0.181884765625},{"x":0.0643310546875,"y":0.078094482421875},{"x":-0.168975830078125,"y":0.442962646484375},{"x":0.167236328125,"y":0.161346435546875},{"x":-0.11376953125,"y":-0.179351806640625},{"x":0.16351318359375,"y":0.17645263671875},{"x":0.1360626220703125,"y":0.1256103515625},{"x":0.253997802734375,"y":0.4302978515625},{"x":-7.32421875E-4,"y":0.034210205078125},{"x":-0.046356201171875,"y":0.138214111328125},{"x":0.0111083984375,"y":0.10272216796875},{"x":-0.102294921875,"y":0.006195068359375},{"x":-0.172882080078125,"y":-0.42401123046875}],"optimisedCameraToObject":{"translation":{"x":-0.12044170011989679,"y":-0.02906312498524957,"z":0.48790735444749955},"rotation":{"quaternion":{"W":0.9932715454145365,"X":0.10653308304703156,"Y":-0.027799516241507824,"Z":0.035909973308967266}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":205.10565185546875,"y":291.9783630371094},{"x":239.94932556152344,"y":295.44097900390625},{"x":274.6065979003906,"y":298.9404602050781},{"x":309.19268798828125,"y":302.4843444824219},{"x":343.50250244140625,"y":306.2490234375},{"x":378.12286376953125,"y":309.4586181640625},{"x":412.1042175292969,"y":312.9718933105469},{"x":203.35182189941406,"y":325.5445861816406},{"x":237.86865234375,"y":328.9479064941406},{"x":272.10772705078125,"y":332.2984313964844},{"x":306.1739196777344,"y":336.0998840332031},{"x":340.2659912109375,"y":339.60003662109375},{"x":374.4324645996094,"y":342.9143371582031},{"x":408.437255859375,"y":346.14447021484375},{"x":201.40093994140625,"y":358.6287841796875},{"x":235.3829803466797,"y":361.6885681152344},{"x":269.5810546875,"y":364.9986877441406},{"x":303.4736328125,"y":368.2331848144531},{"x":337.06976318359375,"y":371.966064453125},{"x":370.9389953613281,"y":375.40655517578125},{"x":404.63348388671875,"y":378.72589111328125},{"x":199.79217529296875,"y":391.0230407714844},{"x":233.54922485351562,"y":394.2126770019531},{"x":267.067626953125,"y":397.4864807128906},{"x":300.750244140625,"y":400.99755859375},{"x":334.1797790527344,"y":404.2261047363281},{"x":367.87017822265625,"y":407.6087341308594},{"x":400.82958984375,"y":410.6313781738281},{"x":197.92198181152344,"y":422.27398681640625},{"x":231.09629821777344,"y":425.1934814453125},{"x":264.6482849121094,"y":428.81256103515625},{"x":297.9969787597656,"y":431.92425537109375},{"x":331.11083984375,"y":435.20733642578125},{"x":364.4385986328125,"y":438.3575439453125},{"x":397.276123046875,"y":441.85955810546875},{"x":196.3050994873047,"y":453.31884765625},{"x":229.6171112060547,"y":456.65960693359375},{"x":262.2696533203125,"y":459.7550354003906},{"x":295.460205078125,"y":463.0153503417969},{"x":328.1221008300781,"y":466.1530456542969},{"x":360.9857177734375,"y":469.7958679199219},{"x":393.6920166015625,"y":473.16229248046875},{"x":194.73199462890625,"y":483.7914123535156},{"x":227.05288696289062,"y":486.9148254394531},{"x":260.13983154296875,"y":490.3260192871094},{"x":292.7618713378906,"y":493.52716064453125},{"x":325.1023864746094,"y":496.80108642578125},{"x":357.75872802734375,"y":499.8298034667969},{"x":389.9835510253906,"y":503.1544494628906}],"reprojectionErrors":[{"x":0.0834808349609375,"y":-0.03680419921875},{"x":-0.110626220703125,"y":0.04754638671875},{"x":-0.151763916015625,"y":0.080596923828125},{"x":-0.1624755859375,"y":0.054168701171875},{"x":0.055023193359375,"y":-0.20892333984375},{"x":-0.0933837890625,"y":0.066497802734375},{"x":0.334625244140625,"y":0.021026611328125},{"x":-0.020538330078125,"y":0.02130126953125},{"x":-0.231353759765625,"y":0.110107421875},{"x":-0.1968994140625,"y":0.235137939453125},{"x":-0.029296875,"y":-0.1080322265625},{"x":0.0655517578125,"y":-0.1678466796875},{"x":0.032012939453125,"y":-0.060455322265625},{"x":0.099029541015625,"y":0.111785888671875},{"x":0.116943359375,"y":-0.110321044921875},{"x":0.10260009765625,"y":0.26849365234375},{"x":-0.159393310546875,"y":0.378326416015625},{"x":-0.15460205078125,"y":0.544464111328125},{"x":0.1009521484375,"y":0.1922607421875},{"x":0.03070068359375,"y":0.11175537109375},{"x":0.075531005859375,"y":0.131134033203125},{"x":-0.044281005859375,"y":-0.208404541015625},{"x":-0.1668548583984375,"y":-0.011688232421875},{"x":-0.08154296875,"y":0.080230712890625},{"x":-0.198150634765625,"y":-0.08642578125},{"x":-0.106231689453125,"y":0.007537841796875},{"x":-0.32659912109375,"y":-0.075164794921875},{"x":0.125732421875,"y":0.178924560546875},{"x":0.0982818603515625,"y":0.19537353515625},{"x":0.2302093505859375,"y":0.6112060546875},{"x":-0.045440673828125,"y":0.304931640625},{"x":-0.154510498046875,"y":0.48284912109375},{"x":-0.072235107421875,"y":0.465606689453125},{"x":-0.254058837890625,"y":0.556793212890625},{"x":-0.002532958984375,"y":0.27117919921875},{"x":0.02886962890625,"y":0.17828369140625},{"x":-0.3001861572265625,"y":0.123016357421875},{"x":0.0010986328125,"y":0.28875732421875},{"x":-0.271392822265625,"y":0.26458740234375},{"x":-0.057647705078125,"y":0.337493896484375},{"x":-0.0946044921875,"y":-0.120941162109375},{"x":-0.02984619140625,"y":-0.3297119140625},{"x":-0.0439300537109375,"y":0.12066650390625},{"x":0.29962158203125,"y":0.234100341796875},{"x":-0.151214599609375,"y":0.03363037109375},{"x":-0.1719970703125,"y":0.016510009765625},{"x":0.04736328125,"y":-0.100677490234375},{"x":-0.096954345703125,"y":-5.4931640625E-4},{"x":0.136016845703125,"y":-0.22479248046875}],"optimisedCameraToObject":{"translation":{"x":-0.1444603335331757,"y":-0.030404896992126864,"z":0.495286899645309},"rotation":{"quaternion":{"W":0.9935961722437695,"X":0.10069740179682722,"Y":-0.0020582638348391586,"Z":0.05120979714746115}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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.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.83456420898438,"y":296.89715576171875},{"x":254.24002075195312,"y":301.42095947265625},{"x":286.8036804199219,"y":306.6441955566406},{"x":320.20489501953125,"y":311.66754150390625},{"x":353.6714172363281,"y":316.728271484375},{"x":387.8068542480469,"y":321.7738952636719},{"x":422.03546142578125,"y":326.951171875},{"x":219.277587890625,"y":329.386962890625},{"x":251.4307098388672,"y":334.3419494628906},{"x":283.6063232421875,"y":339.70355224609375},{"x":316.5751647949219,"y":344.91058349609375},{"x":349.55694580078125,"y":349.8240051269531},{"x":383.6032409667969,"y":355.2890319824219},{"x":417.7720031738281,"y":360.52203369140625},{"x":216.86907958984375,"y":361.63421630859375},{"x":248.5254364013672,"y":366.6168212890625},{"x":280.7945251464844,"y":371.8406066894531},{"x":313.29486083984375,"y":377.10528564453125},{"x":345.91595458984375,"y":382.8291320800781},{"x":379.39862060546875,"y":388.3311462402344},{"x":412.92169189453125,"y":393.7823791503906},{"x":214.70777893066406,"y":392.9633483886719},{"x":246.13912963867188,"y":398.3952331542969},{"x":277.6194763183594,"y":404.005615234375},{"x":309.6116638183594,"y":409.62298583984375},{"x":342.3776550292969,"y":415.0847473144531},{"x":375.45782470703125,"y":420.7248229980469},{"x":408.8182373046875,"y":426.4452209472656},{"x":212.2794647216797,"y":423.63482666015625},{"x":243.24232482910156,"y":429.1402893066406},{"x":274.7992858886719,"y":434.8668212890625},{"x":306.69940185546875,"y":440.710693359375},{"x":338.7595520019531,"y":446.4786682128906},{"x":371.6744079589844,"y":452.53411865234375},{"x":404.6105651855469,"y":458.5321960449219},{"x":209.92945861816406,"y":454.25665283203125},{"x":240.64459228515625,"y":459.9393005371094},{"x":271.74884033203125,"y":465.6007080078125},{"x":303.5716857910156,"y":471.75177001953125},{"x":335.2811584472656,"y":477.7835693359375},{"x":367.634521484375,"y":483.88330078125},{"x":400.1826171875,"y":489.9425964355469},{"x":207.46145629882812,"y":484.11260986328125},{"x":237.98487854003906,"y":489.9325256347656},{"x":268.79022216796875,"y":496.08447265625},{"x":300.03961181640625,"y":502.2381286621094},{"x":331.57110595703125,"y":508.223388671875},{"x":363.7362060546875,"y":514.6088256835938},{"x":396.0698547363281,"y":520.8773803710938}],"reprojectionErrors":[{"x":0.1796875,"y":-0.1329345703125},{"x":-0.0954437255859375,"y":0.2276611328125},{"x":-0.041900634765625,"y":-0.048095703125},{"x":-0.335235595703125,"y":-0.060455322265625},{"x":-0.199462890625,"y":-0.04644775390625},{"x":-0.234527587890625,"y":0.046783447265625},{"x":0.138824462890625,"y":0.07275390625},{"x":0.1864776611328125,"y":0.033416748046875},{"x":-0.1408233642578125,"y":0.1556396484375},{"x":-0.0123291015625,"y":-0.065643310546875},{"x":-0.195098876953125,"y":-0.069000244140625},{"x":0.094696044921875,"y":0.284942626953125},{"x":-0.191009521484375,"y":0.151153564453125},{"x":-0.1068115234375,"y":0.3135986328125},{"x":0.101287841796875,"y":-0.137725830078125},{"x":-0.029327392578125,"y":0.1419677734375},{"x":-0.30279541015625,"y":0.243438720703125},{"x":-0.3341064453125,"y":0.367218017578125},{"x":-0.00933837890625,"y":0.09527587890625},{"x":-0.066009521484375,"y":0.108856201171875},{"x":0.3203125,"y":0.237060546875},{"x":-0.175750732421875,"y":0.04034423828125},{"x":-0.37713623046875,"y":0.048248291015625},{"x":-0.165863037109375,"y":-0.059539794921875},{"x":-0.001373291015625,"y":-0.111328125},{"x":-0.142333984375,"y":0.0556640625},{"x":-0.1259765625,"y":0.107666015625},{"x":0.084716796875,"y":0.14288330078125},{"x":-0.131561279296875,"y":0.317901611328125},{"x":-0.156005859375,"y":0.4224853515625},{"x":-0.320892333984375,"y":0.3685302734375},{"x":-0.3720703125,"y":0.259918212890625},{"x":-0.123260498046875,"y":0.290069580078125},{"x":-0.266082763671875,"y":0.095703125},{"x":0.035797119140625,"y":0.02178955078125},{"x":-0.112579345703125,"y":0.0975341796875},{"x":-0.1766815185546875,"y":0.188140869140625},{"x":-0.184112548828125,"y":0.3621826171875},{"x":-0.46124267578125,"y":0.10894775390625},{"x":-0.173095703125,"y":0.03741455078125},{"x":-0.074005126953125,"y":-0.039520263671875},{"x":0.287933349609375,"y":-0.013397216796875},{"x":0.0764312744140625,"y":0.1058349609375},{"x":-0.07928466796875,"y":0.215576171875},{"x":-0.07879638671875,"y":0.05511474609375},{"x":-0.081268310546875,"y":-0.04510498046875},{"x":0.078125,"y":0.0850830078125},{"x":0.050628662109375,"y":-0.12286376953125},{"x":0.304046630859375,"y":-0.15185546875}],"optimisedCameraToObject":{"translation":{"x":-0.13480977528488933,"y":-0.027969011362889956,"z":0.5153615289954407},"rotation":{"quaternion":{"W":0.9909360988225843,"X":0.0871584029591874,"Y":0.07865896851506536,"Z":0.06528267393441664}}},"includeObservationInCalibration":true,"snapshotName":"img21.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img21.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":273.29534912109375,"y":298.1326904296875},{"x":305.9515380859375,"y":301.1636962890625},{"x":339.3200378417969,"y":304.5674743652344},{"x":373.2886962890625,"y":307.8554382324219},{"x":407.53680419921875,"y":311.25189208984375},{"x":442.29632568359375,"y":314.6498107910156},{"x":477.8211669921875,"y":318.41070556640625},{"x":271.8194885253906,"y":331.2152099609375},{"x":304.8092346191406,"y":334.7142333984375},{"x":337.31109619140625,"y":337.9703369140625},{"x":370.87628173828125,"y":341.93060302734375},{"x":404.7430725097656,"y":345.5891418457031},{"x":439.882568359375,"y":349.10662841796875},{"x":474.5042724609375,"y":352.4245910644531},{"x":270.4390869140625,"y":363.8553466796875},{"x":302.5592346191406,"y":367.2923278808594},{"x":335.3482360839844,"y":371.1324157714844},{"x":368.3153076171875,"y":374.4293518066406},{"x":402.0694885253906,"y":379.07635498046875},{"x":436.4385681152344,"y":382.52679443359375},{"x":471.5690612792969,"y":386.81878662109375},{"x":269.3453369140625,"y":395.74066162109375},{"x":301.283935546875,"y":399.8152770996094},{"x":333.4527893066406,"y":403.8787841796875},{"x":366.2280578613281,"y":407.94769287109375},{"x":399.50836181640625,"y":411.8315734863281},{"x":433.6887512207031,"y":416.33135986328125},{"x":468.0879211425781,"y":420.1074523925781},{"x":267.9858703613281,"y":426.98883056640625},{"x":299.7019958496094,"y":431.1611328125},{"x":331.33642578125,"y":435.3774719238281},{"x":364.2884521484375,"y":439.9194641113281},{"x":397.2591857910156,"y":444.1138000488281},{"x":431.10693359375,"y":448.3982238769531},{"x":465.14642333984375,"y":453.09429931640625},{"x":266.5639343261719,"y":458.08367919921875},{"x":298.15924072265625,"y":462.63189697265625},{"x":329.7684631347656,"y":466.9753112792969},{"x":362.11083984375,"y":471.44439697265625},{"x":394.8540344238281,"y":476.1927795410156},{"x":427.86859130859375,"y":481.2795715332031},{"x":462.1605224609375,"y":486.0140686035156},{"x":265.30596923828125,"y":488.6055908203125},{"x":296.1524658203125,"y":492.899169921875},{"x":327.7750549316406,"y":498.2210998535156},{"x":359.7512512207031,"y":502.6278991699219},{"x":392.3768615722656,"y":507.77685546875},{"x":425.5109558105469,"y":512.5757446289062},{"x":459.2100830078125,"y":517.9026489257812}],"reprojectionErrors":[{"x":0.16204833984375,"y":-0.04644775390625},{"x":0.0906982421875,"y":0.164642333984375},{"x":-0.11419677734375,"y":0.051483154296875},{"x":-0.332489013671875,"y":0.103240966796875},{"x":-0.23529052734375,"y":0.096160888671875},{"x":-0.046478271484375,"y":0.1378173828125},{"x":-0.01177978515625,"y":-0.132720947265625},{"x":0.18157958984375,"y":-0.069580078125},{"x":-0.494293212890625,"y":-0.06915283203125},{"x":-0.11273193359375,"y":0.224456787109375},{"x":-0.21710205078125,"y":-0.135345458984375},{"x":-0.037841796875,"y":-0.142059326171875},{"x":-0.53814697265625,"y":0.044158935546875},{"x":0.080322265625,"y":0.482330322265625},{"x":0.138427734375,"y":-0.173858642578125},{"x":0.064300537109375,"y":0.1373291015625},{"x":-0.118133544921875,"y":0.09716796875},{"x":0.089508056640625,"y":0.65252685546875},{"x":0.085845947265625,"y":-0.08929443359375},{"x":0.0506591796875,"y":0.41888427734375},{"x":-0.1549072265625,"y":0.139404296875},{"x":-0.1591796875,"y":-0.038818359375},{"x":-0.3165283203125,"y":-0.125030517578125},{"x":-0.15240478515625,"y":-0.14691162109375},{"x":-0.035614013671875,"y":-0.120391845703125},{"x":0.14263916015625,"y":0.14544677734375},{"x":-0.005340576171875,"y":-0.14984130859375},{"x":0.20916748046875,"y":0.333892822265625},{"x":-0.15948486328125,"y":0.2257080078125},{"x":-0.356048583984375,"y":0.27386474609375},{"x":0.072113037109375,"y":0.33258056640625},{"x":-0.26708984375,"y":0.120697021484375},{"x":-0.067657470703125,"y":0.31201171875},{"x":-0.18072509765625,"y":0.46929931640625},{"x":0.086151123046875,"y":0.271484375},{"x":-0.066253662109375,"y":0.143707275390625},{"x":-0.400726318359375,"y":0.040069580078125},{"x":-0.21453857421875,"y":0.196990966796875},{"x":-0.22003173828125,"y":0.284454345703125},{"x":-0.07794189453125,"y":0.149383544921875},{"x":0.348175048828125,"y":-0.266937255859375},{"x":0.059173583984375,"y":-0.273345947265625},{"x":-0.10650634765625,"y":0.1424560546875},{"x":0.0521240234375,"y":0.50982666015625},{"x":-0.039154052734375,"y":-0.0943603515625},{"x":0.04888916015625,"y":0.27392578125},{"x":0.02716064453125,"y":-0.042205810546875},{"x":0.0433349609375,"y":0.0499267578125},{"x":0.047515869140625,"y":-0.327392578125}],"optimisedCameraToObject":{"translation":{"x":-0.0971020601485617,"y":-0.02593864395801202,"z":0.5148826016899422},"rotation":{"quaternion":{"W":0.9921238690308274,"X":0.07821680074117643,"Y":0.08912589827431254,"Z":0.04036006488985952}}},"includeObservationInCalibration":true,"snapshotName":"img22.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img22.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.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.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":468.2918395996094,"y":296.106689453125},{"x":503.1427917480469,"y":298.7600402832031},{"x":538.4879150390625,"y":301.4425964355469},{"x":574.1312866210938,"y":304.1048583984375},{"x":610.0447387695312,"y":307.3140563964844},{"x":430.15582275390625,"y":327.8674621582031},{"x":465.0914001464844,"y":330.5533447265625},{"x":500.1175537109375,"y":333.4758605957031},{"x":535.0822143554688,"y":336.2174987792969},{"x":570.7398681640625,"y":339.1258544921875},{"x":606.171142578125,"y":341.5516662597656},{"x":393.27813720703125,"y":358.5330810546875},{"x":427.5981140136719,"y":361.21429443359375},{"x":462.24127197265625,"y":364.1380615234375},{"x":496.54742431640625,"y":367.121826171875},{"x":531.6513061523438,"y":370.0340881347656},{"x":566.8878784179688,"y":373.0981140136719},{"x":602.1993408203125,"y":376.3245544433594},{"x":391.0768737792969,"y":391.7809143066406},{"x":425.14215087890625,"y":394.52630615234375},{"x":459.0600280761719,"y":397.5071105957031},{"x":493.3962707519531,"y":401.0244445800781},{"x":528.16845703125,"y":403.8939514160156},{"x":563.2645263671875,"y":407.0942077636719},{"x":598.5987548828125,"y":410.03741455078125},{"x":422.43670654296875,"y":426.96051025390625},{"x":456.1813659667969,"y":430.0790100097656},{"x":490.6443786621094,"y":433.4365539550781},{"x":524.7940063476562,"y":436.4040832519531},{"x":559.907470703125,"y":439.93731689453125},{"x":594.4887084960938,"y":443.41668701171875},{"x":419.745849609375,"y":459.8104248046875},{"x":453.426025390625,"y":462.6128234863281},{"x":487.55181884765625,"y":466.18951416015625},{"x":521.5829467773438,"y":469.70831298828125},{"x":556.5078735351562,"y":473.1047058105469},{"x":417.490478515625,"y":491.7756042480469},{"x":451.0010681152344,"y":495.0631103515625},{"x":553.0160522460938,"y":505.3081970214844}],"reprojectionErrors":[{"x":-0.38311767578125,"y":0.103363037109375},{"x":-0.06243896484375,"y":0.16339111328125},{"x":0.04510498046875,"y":0.20965576171875},{"x":0.131103515625,"y":0.291259765625},{"x":0.21905517578125,"y":-0.159454345703125},{"x":0.169097900390625,"y":-0.19097900390625},{"x":-0.12225341796875,"y":-0.056610107421875},{"x":-0.222625732421875,"y":-0.14459228515625},{"x":0.01593017578125,"y":-0.037872314453125},{"x":-0.16546630859375,"y":-0.08447265625},{"x":0.1480712890625,"y":0.364349365234375},{"x":0.2630615234375,"y":-0.0736083984375},{"x":0.065032958984375,"y":0.171356201171875},{"x":-0.17431640625,"y":0.186981201171875},{"x":0.201263427734375,"y":0.155303955078125},{"x":0.052978515625,"y":0.2073974609375},{"x":0.04150390625,"y":0.119476318359375},{"x":0.22015380859375,"y":-0.119659423828125},{"x":0.072906494140625,"y":-0.179718017578125},{"x":-0.105499267578125,"y":0.1181640625},{"x":0.14178466796875,"y":0.19232177734375},{"x":0.24505615234375,"y":-0.25885009765625},{"x":0.18267822265625,"y":-0.051513671875},{"x":0.06243896484375,"y":-0.164794921875},{"x":-0.034423828125,"y":-0.011444091796875},{"x":0.0084228515625,"y":0.496734619140625},{"x":0.191986083984375,"y":0.54534912109375},{"x":-0.071929931640625,"y":0.36456298828125},{"x":0.24432373046875,"y":0.582977294921875},{"x":-0.1407470703125,"y":0.24420166015625},{"x":0.2646484375,"y":-0.03271484375},{"x":0.142364501953125,"y":0.01800537109375},{"x":0.1552734375,"y":0.491424560546875},{"x":-0.010101318359375,"y":0.198760986328125},{"x":0.18255615234375,"y":-0.02838134765625},{"x":-0.2593994140625,"y":-0.126129150390625},{"x":-0.124908447265625,"y":-0.013275146484375},{"x":-0.17584228515625,"y":0.0804443359375},{"x":-0.244384765625,"y":0.01702880859375}],"optimisedCameraToObject":{"translation":{"x":-0.004001931220753106,"y":-0.030982526374607623,"z":0.5021405477424915},"rotation":{"quaternion":{"W":0.9963181190503495,"X":0.06513141171567187,"Y":0.042500968253930876,"Z":0.03608008532938393}}},"includeObservationInCalibration":true,"snapshotName":"img23.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img23.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":482.1957702636719,"y":290.4354553222656},{"x":516.843994140625,"y":292.57684326171875},{"x":551.3347778320312,"y":294.9490051269531},{"x":586.267333984375,"y":297.1055908203125},{"x":620.8065795898438,"y":299.3494873046875},{"x":655.568359375,"y":301.1884460449219},{"x":690.2613525390625,"y":303.9497375488281},{"x":479.16192626953125,"y":324.332763671875},{"x":513.6758422851562,"y":326.5758972167969},{"x":547.8634643554688,"y":328.419921875},{"x":582.96875,"y":331.16571044921875},{"x":617.506591796875,"y":333.3865661621094},{"x":652.2415161132812,"y":335.77276611328125},{"x":686.2088623046875,"y":337.69708251953125},{"x":476.7009582519531,"y":357.86236572265625},{"x":510.6234130859375,"y":359.9443359375},{"x":544.8506469726562,"y":362.2239074707031},{"x":578.8770141601562,"y":364.2187194824219},{"x":613.531982421875,"y":367.0957336425781},{"x":647.8619384765625,"y":369.0498046875},{"x":682.4725341796875,"y":371.5747985839844},{"x":473.8480224609375,"y":390.925048828125},{"x":507.73211669921875,"y":393.1667175292969},{"x":541.5873413085938,"y":395.46063232421875},{"x":575.7974853515625,"y":398.0694274902344},{"x":610.00732421875,"y":400.4812316894531},{"x":644.3345336914062,"y":402.9371337890625},{"x":678.472900390625,"y":404.9878845214844},{"x":471.0480651855469,"y":423.138671875},{"x":504.8868713378906,"y":425.3839416503906},{"x":538.5502319335938,"y":428.0508117675781},{"x":572.7108154296875,"y":430.4819641113281},{"x":606.2509765625,"y":432.857666015625},{"x":640.8463745117188,"y":435.0709533691406},{"x":674.7277221679688,"y":437.7785339355469},{"x":468.33349609375,"y":455.7919616699219},{"x":501.95001220703125,"y":458.14349365234375},{"x":535.3115844726562,"y":460.45391845703125},{"x":569.1876220703125,"y":462.9403076171875},{"x":602.9607543945312,"y":465.513916015625},{"x":636.8878173828125,"y":468.1390380859375},{"x":670.8754272460938,"y":470.7610778808594},{"x":465.7239074707031,"y":487.1983337402344},{"x":498.99853515625,"y":489.730712890625},{"x":532.685546875,"y":492.5281982421875},{"x":566.007080078125,"y":495.0296630859375},{"x":599.5563354492188,"y":497.6811828613281},{"x":633.0881958007812,"y":499.95343017578125},{"x":667.0059814453125,"y":502.67681884765625}],"reprojectionErrors":[{"x":-0.040863037109375,"y":-0.18994140625},{"x":-0.1661376953125,"y":-0.060302734375},{"x":-0.02496337890625,"y":-0.159454345703125},{"x":-0.2236328125,"y":-0.041534423828125},{"x":0.06597900390625,"y":-0.009918212890625},{"x":0.22088623046875,"y":0.427154541015625},{"x":0.52520751953125,"y":-0.05810546875},{"x":0.222503662109375,"y":-0.170135498046875},{"x":0.01739501953125,"y":-0.097564697265625},{"x":0.246337890625,"y":0.373779296875},{"x":-0.3414306640625,"y":-0.057464599609375},{"x":-0.26788330078125,"y":0.034912109375},{"x":-0.304443359375,"y":-0.03985595703125},{"x":0.50634765625,"y":0.34490966796875},{"x":-0.057159423828125,"y":-0.197418212890625},{"x":0.116119384765625,"y":0.07958984375},{"x":0.09124755859375,"y":0.15643310546875},{"x":0.36700439453125,"y":0.514984130859375},{"x":0.10711669921875,"y":-0.01226806640625},{"x":0.25830078125,"y":0.37933349609375},{"x":0.20782470703125,"y":0.19537353515625},{"x":0.084808349609375,"y":-0.169677734375},{"x":0.08447265625,"y":-0.010406494140625},{"x":0.21844482421875,"y":0.09185791015625},{"x":0.09625244140625,"y":-0.126007080078125},{"x":0.0662841796875,"y":-0.15264892578125},{"x":0.00408935546875,"y":-0.229766845703125},{"x":0.20892333984375,"y":0.0914306640625},{"x":0.203277587890625,"y":0.29827880859375},{"x":0.037353515625,"y":0.49456787109375},{"x":0.151123046875,"y":0.262420654296875},{"x":-0.13458251953125,"y":0.258575439453125},{"x":0.29107666015625,"y":0.302215576171875},{"x":-0.25421142578125,"y":0.499786376953125},{"x":-0.0081787109375,"y":0.1939697265625},{"x":0.265655517578125,"y":-0.079254150390625},{"x":0.11224365234375,"y":0.050140380859375},{"x":0.31695556640625,"y":0.21173095703125},{"x":0.10382080078125,"y":0.187835693359375},{"x":0.0836181640625,"y":0.066650390625},{"x":-0.0072021484375,"y":-0.116668701171875},{"x":-0.08203125,"y":-0.30810546875},{"x":0.252227783203125,"y":0.38739013671875},{"x":0.232025146484375,"y":0.37408447265625},{"x":-0.0985107421875,"y":0.08465576171875},{"x":0.03204345703125,"y":0.0797119140625},{"x":0.02398681640625,"y":-0.08740234375},{"x":0.11572265625,"y":0.112030029296875},{"x":-0.10272216796875,"y":-0.1529541015625}],"optimisedCameraToObject":{"translation":{"x":0.05776809839648845,"y":-0.03118119563322978,"z":0.5040427226881621},"rotation":{"quaternion":{"W":0.9974562098786715,"X":0.06120279982333776,"Y":0.017808462751924305,"Z":0.03190901632256216}}},"includeObservationInCalibration":true,"snapshotName":"img24.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img24.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":514.5296020507812,"y":301.00286865234375},{"x":548.6827392578125,"y":302.5894470214844},{"x":582.6654052734375,"y":303.99432373046875},{"x":616.832275390625,"y":305.2751159667969},{"x":650.9384765625,"y":307.00567626953125},{"x":685.708740234375,"y":308.418212890625},{"x":720.0001220703125,"y":310.0417785644531},{"x":512.157958984375,"y":333.8208923339844},{"x":545.93603515625,"y":335.31146240234375},{"x":579.6051635742188,"y":336.9882507324219},{"x":613.8090209960938,"y":338.5982360839844},{"x":647.8197631835938,"y":340.02691650390625},{"x":681.928955078125,"y":341.5901794433594},{"x":715.858154296875,"y":342.9744873046875},{"x":509.88812255859375,"y":366.0136413574219},{"x":543.0414428710938,"y":367.639892578125},{"x":576.8389892578125,"y":369.0639953613281},{"x":610.2348022460938,"y":370.8179626464844},{"x":644.02001953125,"y":372.4911804199219},{"x":678.0465087890625,"y":374.06463623046875},{"x":711.7077026367188,"y":375.7767333984375},{"x":507.4109802246094,"y":397.91455078125},{"x":540.4078979492188,"y":399.520751953125},{"x":573.8142700195312,"y":401.10186767578125},{"x":607.1807861328125,"y":403.0011291503906},{"x":640.6928100585938,"y":404.4811706542969},{"x":674.551025390625,"y":406.4023742675781},{"x":707.8875732421875,"y":407.9593811035156},{"x":504.9230651855469,"y":428.69195556640625},{"x":537.8804931640625,"y":430.3636169433594},{"x":570.8968505859375,"y":432.1441955566406},{"x":604.033203125,"y":433.8566589355469},{"x":637.201416015625,"y":435.8022766113281},{"x":670.618408203125,"y":437.323974609375},{"x":704.0753173828125,"y":439.16754150390625},{"x":502.61309814453125,"y":459.3592529296875},{"x":535.2446899414062,"y":461.3779602050781},{"x":567.8731079101562,"y":462.93212890625},{"x":601.0425415039062,"y":464.8209228515625},{"x":633.9627685546875,"y":466.8599853515625},{"x":666.9378662109375,"y":468.8481750488281},{"x":700.0917358398438,"y":470.5336608886719},{"x":500.60418701171875,"y":489.4859619140625},{"x":532.8828125,"y":491.39837646484375},{"x":565.3642578125,"y":493.39178466796875},{"x":597.9903564453125,"y":495.1634216308594},{"x":630.6166381835938,"y":497.10296630859375},{"x":663.4273681640625,"y":499.06134033203125},{"x":696.3583984375,"y":501.038818359375}],"reprojectionErrors":[{"x":0.07763671875,"y":-0.057952880859375},{"x":-0.12841796875,"y":-0.111297607421875},{"x":-0.01495361328125,"y":0.0155029296875},{"x":0.05712890625,"y":0.26446533203125},{"x":0.32647705078125,"y":0.061431884765625},{"x":0.06201171875,"y":0.173828125},{"x":0.40020751953125,"y":0.072296142578125},{"x":0.05413818359375,"y":-0.065582275390625},{"x":-0.0650634765625,"y":0.0413818359375},{"x":0.0712890625,"y":-0.04144287109375},{"x":-0.18658447265625,"y":-0.06134033203125},{"x":-0.116943359375,"y":0.0958251953125},{"x":-0.017578125,"y":0.11376953125},{"x":0.38360595703125,"y":0.30572509765625},{"x":-0.036163330078125,"y":0.003265380859375},{"x":0.18450927734375,"y":0.036407470703125},{"x":-0.09478759765625,"y":0.2662353515625},{"x":0.16595458984375,"y":0.160369873046875},{"x":0.16949462890625,"y":0.12908935546875},{"x":0.057861328125,"y":0.19097900390625},{"x":0.431396484375,"y":0.107269287109375},{"x":0.11529541015625,"y":-0.175537109375},{"x":0.21087646484375,"y":-0.062835693359375},{"x":0.03887939453125,"y":0.067657470703125},{"x":0.0428466796875,"y":-0.127685546875},{"x":0.03143310546875,"y":0.088134765625},{"x":-0.20208740234375,"y":-0.145721435546875},{"x":0.20391845703125,"y":-0.024261474609375},{"x":0.31146240234375,"y":0.238800048828125},{"x":0.16827392578125,"y":0.343292236328125},{"x":0.10577392578125,"y":0.329803466796875},{"x":0.05718994140625,"y":0.37493896484375},{"x":0.1048583984375,"y":0.176971435546875},{"x":0.02581787109375,"y":0.392608642578125},{"x":0.0228271484375,"y":0.275634765625},{"x":0.363067626953125,"y":0.241912841796875},{"x":0.2706298828125,"y":0.054412841796875},{"x":0.31890869140625,"y":0.320648193359375},{"x":-0.0421142578125,"y":0.24102783203125},{"x":-0.02789306640625,"y":-5.79833984375E-4},{"x":0.05157470703125,"y":-0.20343017578125},{"x":0.0665283203125,"y":-0.116119384765625},{"x":0.14642333984375,"y":0.273101806640625},{"x":0.13519287109375,"y":0.24481201171875},{"x":0.056396484375,"y":0.123077392578125},{"x":-0.03741455078125,"y":0.210113525390625},{"x":-0.00732421875,"y":0.115875244140625},{"x":-0.04345703125,"y":-0.01104736328125},{"x":-0.0875244140625,"y":-0.171417236328125}],"optimisedCameraToObject":{"translation":{"x":0.08349911855598952,"y":-0.022516339739823543,"z":0.5146657442104814},"rotation":{"quaternion":{"W":0.9957755350079717,"X":0.0861310210406133,"Y":0.024509569201674925,"Z":0.02029315430477627}}},"includeObservationInCalibration":true,"snapshotName":"img25.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img25.png"},{"locationInObjectSpace":[{"x":0.07620000094175339,"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.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.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":521.2957153320312,"y":177.27716064453125},{"x":626.6957397460938,"y":182.89825439453125},{"x":661.4932250976562,"y":184.82521057128906},{"x":448.86859130859375,"y":209.07960510253906},{"x":484.162353515625,"y":211.08653259277344},{"x":519.0791015625,"y":212.4941864013672},{"x":625.0225219726562,"y":218.34507751464844},{"x":659.46435546875,"y":219.86172485351562},{"x":482.1783752441406,"y":246.43948364257812},{"x":517.1153564453125,"y":248.09866333007812},{"x":552.4802856445312,"y":249.891845703125},{"x":587.6704711914062,"y":251.80735778808594},{"x":622.8319091796875,"y":253.53207397460938},{"x":657.6852416992188,"y":255.36453247070312},{"x":480.1801452636719,"y":281.88397216796875},{"x":515.2318115234375,"y":283.5365905761719},{"x":550.5081787109375,"y":285.410888671875},{"x":585.7969360351562,"y":287.16094970703125},{"x":620.8564453125,"y":288.9385681152344},{"x":655.7432250976562,"y":290.59576416015625},{"x":443.1548156738281,"y":315.0316162109375},{"x":478.19720458984375,"y":316.6027526855469},{"x":513.4869995117188,"y":318.4105529785156},{"x":548.6257934570312,"y":320.12432861328125},{"x":583.5635986328125,"y":322.0123596191406},{"x":618.98046875,"y":323.7330627441406},{"x":653.74169921875,"y":325.4056396484375},{"x":441.24688720703125,"y":350.4255676269531},{"x":476.53814697265625,"y":352.1204528808594},{"x":511.4320068359375,"y":354.0231628417969},{"x":546.8379516601562,"y":355.7093505859375},{"x":581.85595703125,"y":357.4516906738281},{"x":616.8963012695312,"y":359.1291809082031},{"x":652.02880859375,"y":360.8927307128906},{"x":439.5082702636719,"y":385.57720947265625},{"x":474.5896911621094,"y":387.2275390625},{"x":509.70867919921875,"y":388.9516906738281},{"x":544.9296875,"y":390.67779541015625},{"x":579.8626708984375,"y":392.3709411621094},{"x":615.2136840820312,"y":394.3392333984375},{"x":650.2600708007812,"y":396.0731506347656}],"reprojectionErrors":[{"x":-0.16986083984375,"y":0.046630859375},{"x":-0.0196533203125,"y":-0.028289794921875},{"x":0.25616455078125,"y":-0.0946502685546875},{"x":-0.140655517578125,"y":-0.013031005859375},{"x":-0.1539306640625,"y":-0.2015533447265625},{"x":0.180908203125,"y":0.2139129638671875},{"x":-0.2593994140625,"y":-0.14349365234375},{"x":0.356689453125,"y":0.17767333984375},{"x":-0.0234375,"y":-0.189300537109375},{"x":0.2734375,"y":-0.037750244140625},{"x":0.10577392578125,"y":-0.0185394287109375},{"x":0.0684814453125,"y":-0.1203765869140625},{"x":0.00787353515625,"y":-0.030548095703125},{"x":0.19549560546875,"y":-0.0479888916015625},{"x":0.117828369140625,"y":-0.305023193359375},{"x":0.2806396484375,"y":-0.15936279296875},{"x":0.18231201171875,"y":-0.236328125},{"x":0.0274658203125,"y":-0.190399169921875},{"x":0.0499267578125,"y":-0.173736572265625},{"x":0.18548583984375,"y":-0.03875732421875},{"x":0.06109619140625,"y":0.04583740234375},{"x":0.2406005859375,"y":0.263580322265625},{"x":0.144287109375,"y":0.241546630859375},{"x":0.1627197265625,"y":0.309967041015625},{"x":0.338134765625,"y":0.200225830078125},{"x":-0.0172119140625,"y":0.253509521484375},{"x":0.2236328125,"y":0.350189208984375},{"x":0.1287841796875,"y":-0.09710693359375},{"x":0.03656005859375,"y":-0.013092041015625},{"x":0.313507080078125,"y":-0.142608642578125},{"x":0.04229736328125,"y":-0.061737060546875},{"x":0.11529541015625,"y":-0.043548583984375},{"x":0.11431884765625,"y":0.0325927734375},{"x":-0.0379638671875,"y":0.015380859375},{"x":0.026123046875,"y":-0.048980712890625},{"x":0.119293212890625,"y":0.069580078125},{"x":0.146820068359375,"y":0.105987548828125},{"x":0.03643798828125,"y":0.131744384765625},{"x":0.17047119140625,"y":0.18133544921875},{"x":-0.164794921875,"y":-0.053680419921875},{"x":-0.2545166015625,"y":-0.064178466796875}],"optimisedCameraToObject":{"translation":{"x":0.03245560578291374,"y":-0.11448533298953378,"z":0.49154189789336694},"rotation":{"quaternion":{"W":0.9996548030252677,"X":0.005596337866809827,"Y":-0.003718129262452472,"Z":0.02539943514689826}}},"includeObservationInCalibration":true,"snapshotName":"img26.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img26.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.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.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":465.79461669921875,"y":194.57469177246094},{"x":500.9768371582031,"y":197.2300262451172},{"x":535.7828979492188,"y":199.96719360351562},{"x":570.7738037109375,"y":202.45094299316406},{"x":605.1046142578125,"y":205.14010620117188},{"x":427.94805908203125,"y":227.7534637451172},{"x":462.7135925292969,"y":230.26995849609375},{"x":498.13446044921875,"y":232.8081817626953},{"x":532.9523315429688,"y":235.29562377929688},{"x":567.8305053710938,"y":237.89820861816406},{"x":601.9569091796875,"y":240.29925537109375},{"x":389.8349914550781,"y":260.6741638183594},{"x":424.863037109375,"y":263.0618896484375},{"x":460.031982421875,"y":265.7435607910156},{"x":494.95513916015625,"y":268.2080078125},{"x":529.8604125976562,"y":270.570068359375},{"x":387.09405517578125,"y":296.1213073730469},{"x":422.1976623535156,"y":298.72918701171875},{"x":457.18328857421875,"y":301.1380920410156},{"x":492.13519287109375,"y":303.6350402832031},{"x":527.0037231445312,"y":305.9007873535156},{"x":384.38800048828125,"y":331.2514343261719},{"x":419.47210693359375,"y":333.2155456542969},{"x":454.5055236816406,"y":335.83587646484375},{"x":489.3376770019531,"y":338.0233154296875},{"x":524.1068115234375,"y":340.41290283203125},{"x":558.6611938476562,"y":342.6106262207031},{"x":593.001953125,"y":345.28448486328125},{"x":381.8795471191406,"y":366.25732421875},{"x":416.95965576171875,"y":368.64910888671875},{"x":451.68890380859375,"y":370.8818664550781},{"x":486.6841735839844,"y":373.0665283203125},{"x":520.9815673828125,"y":375.2961730957031},{"x":555.8981323242188,"y":377.72418212890625},{"x":590.01171875,"y":380.08001708984375},{"x":379.280029296875,"y":401.224365234375},{"x":414.2626037597656,"y":403.2995910644531},{"x":449.23895263671875,"y":405.67047119140625},{"x":483.8260498046875,"y":407.76580810546875},{"x":518.4837036132812,"y":410.06036376953125},{"x":552.9310913085938,"y":412.3166809082031},{"x":587.213623046875,"y":414.57635498046875}],"reprojectionErrors":[{"x":-0.150299072265625,"y":-0.0428466796875},{"x":-0.14776611328125,"y":-0.0226287841796875},{"x":0.0731201171875,"y":-0.0906524658203125},{"x":-0.05548095703125,"y":0.0877685546875},{"x":0.3048095703125,"y":0.0532379150390625},{"x":-0.31622314453125,"y":-0.1902923583984375},{"x":0.1729736328125,"y":-0.1023406982421875},{"x":-0.1431884765625,"y":-0.0443267822265625},{"x":-0.01324462890625,"y":0.0557861328125},{"x":-0.10723876953125,"y":0.0315093994140625},{"x":0.3802490234375,"y":0.19903564453125},{"x":-0.1851806640625,"y":-0.110565185546875},{"x":0.10137939453125,"y":0.03973388671875},{"x":0.104888916015625,"y":-0.1138916015625},{"x":0.205108642578125,"y":-0.060791015625},{"x":0.167236328125,"y":0.083740234375},{"x":-0.01763916015625,"y":-0.1239013671875},{"x":0.10894775390625,"y":-0.2672119140625},{"x":0.2122802734375,"y":-0.223846435546875},{"x":0.201171875,"y":-0.28131103515625},{"x":0.118408203125,"y":-0.120758056640625},{"x":0.126251220703125,"y":-0.002593994140625},{"x":0.186676025390625,"y":0.42498779296875},{"x":0.157470703125,"y":0.181793212890625},{"x":0.182220458984375,"y":0.3564453125},{"x":0.115966796875,"y":0.313507080078125},{"x":0.10369873046875,"y":0.446563720703125},{"x":0.13775634765625,"y":0.08721923828125},{"x":0.08404541015625,"y":0.0570068359375},{"x":0.06158447265625,"y":-0.015350341796875},{"x":0.250518798828125,"y":0.05450439453125},{"x":0.027099609375,"y":0.155181884765625},{"x":0.34844970703125,"y":0.1932373046875},{"x":-0.109130859375,"y":0.014923095703125},{"x":0.0699462890625,"y":-0.109649658203125},{"x":0.144683837890625,"y":-0.0340576171875},{"x":0.13165283203125,"y":0.138519287109375},{"x":-0.01373291015625,"y":-0.003631591796875},{"x":0.084716796875,"y":0.110321044921875},{"x":-0.03948974609375,"y":0.005218505859375},{"x":-0.11224365234375,"y":-0.081817626953125},{"x":-0.1854248046875,"y":-0.1927490234375}],"optimisedCameraToObject":{"translation":{"x":-0.007154790224406726,"y":-0.10307650220735307,"z":0.48521603743761177},"rotation":{"quaternion":{"W":0.9988833122335768,"X":0.02516842088777473,"Y":-0.018893106519572517,"Z":0.03523818464868207}}},"includeObservationInCalibration":true,"snapshotName":"img27.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img27.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.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":405.9717712402344,"y":312.1780700683594},{"x":440.0703430175781,"y":314.48394775390625},{"x":473.9410705566406,"y":316.65850830078125},{"x":507.50042724609375,"y":319.07305908203125},{"x":541.0534057617188,"y":321.5313415527344},{"x":335.9266052246094,"y":340.1058044433594},{"x":369.7655029296875,"y":342.3905944824219},{"x":403.8347473144531,"y":345.3943176269531},{"x":436.9797668457031,"y":347.1905517578125},{"x":470.2457275390625,"y":349.2221984863281},{"x":503.8778076171875,"y":351.8309020996094},{"x":536.8812255859375,"y":353.7036437988281},{"x":333.94061279296875,"y":372.3429870605469},{"x":367.0425720214844,"y":374.1631164550781},{"x":400.9522399902344,"y":376.58343505859375},{"x":433.7161560058594,"y":378.8739013671875},{"x":467.01068115234375,"y":381.377197265625},{"x":500.1578369140625,"y":383.566650390625},{"x":533.0794067382812,"y":385.859619140625},{"x":332.0982971191406,"y":403.976318359375},{"x":365.041748046875,"y":405.9576416015625},{"x":397.90386962890625,"y":408.5167541503906},{"x":430.8712463378906,"y":410.776611328125},{"x":463.5533447265625,"y":412.755615234375},{"x":496.89251708984375,"y":415.02545166015625},{"x":529.2699584960938,"y":417.4015808105469},{"x":330.1229248046875,"y":434.2522277832031},{"x":362.68280029296875,"y":436.4964599609375},{"x":395.08074951171875,"y":438.74853515625},{"x":428.11334228515625,"y":441.34747314453125},{"x":460.5318298339844,"y":443.1285705566406},{"x":492.90771484375,"y":445.2727355957031},{"x":525.2457275390625,"y":447.72918701171875},{"x":327.9172668457031,"y":464.5654296875},{"x":360.35906982421875,"y":467.0973815917969},{"x":392.7766418457031,"y":469.15380859375},{"x":425.1654052734375,"y":471.1559143066406},{"x":457.15814208984375,"y":473.3932800292969},{"x":489.4927062988281,"y":476.0495910644531},{"x":521.605712890625,"y":477.9019470214844},{"x":326.2951965332031,"y":493.98223876953125},{"x":358.2611389160156,"y":496.1531982421875},{"x":390.130126953125,"y":498.84393310546875},{"x":422.29498291015625,"y":500.98736572265625},{"x":454.16552734375,"y":503.0650634765625},{"x":486.048583984375,"y":505.3249206542969},{"x":517.9661865234375,"y":507.81341552734375}],"reprojectionErrors":[{"x":0.0643310546875,"y":-0.10455322265625},{"x":-0.120819091796875,"y":-0.01263427734375},{"x":-0.120880126953125,"y":0.196441650390625},{"x":0.140716552734375,"y":0.15081787109375},{"x":0.3519287109375,"y":0.04632568359375},{"x":0.120880126953125,"y":-0.040252685546875},{"x":-0.085052490234375,"y":0.062469482421875},{"x":-0.5491943359375,"y":-0.569122314453125},{"x":-0.1239013671875,"y":-0.009033203125},{"x":0.13873291015625,"y":0.29937744140625},{"x":-0.0133056640625,"y":0.014007568359375},{"x":0.40789794921875,"y":0.4473876953125},{"x":0.088348388671875,"y":-0.120025634765625},{"x":0.28009033203125,"y":0.41094970703125},{"x":-0.363006591796875,"y":0.324371337890625},{"x":0.105682373046875,"y":0.349822998046875},{"x":0.003082275390625,"y":0.1441650390625},{"x":4.2724609375E-4,"y":0.233673095703125},{"x":0.169189453125,"y":0.200531005859375},{"x":-0.0455322265625,"y":-0.2509765625},{"x":-0.02923583984375,"y":0.083251953125},{"x":0.041961669921875,"y":-0.1795654296875},{"x":-0.025177001953125,"y":-0.162872314453125},{"x":0.15325927734375,"y":0.114501953125},{"x":-0.37176513671875,"y":0.080474853515625},{"x":0.01202392578125,"y":-0.08087158203125},{"x":-0.005096435546875,"y":0.3359375},{"x":0.066070556640625,"y":0.372589111328125},{"x":0.2734375,"y":0.380279541015625},{"x":-0.186126708984375,"y":0.01953125},{"x":-0.07037353515625,"y":0.45465087890625},{"x":0.042724609375,"y":0.504302978515625},{"x":0.1419677734375,"y":0.2188720703125},{"x":0.305908203125,"y":0.26104736328125},{"x":0.17156982421875,"y":-0.023834228515625},{"x":0.036376953125,"y":0.14385986328125},{"x":-0.10150146484375,"y":0.34259033203125},{"x":0.118804931640625,"y":0.28228759765625},{"x":-0.046966552734375,"y":-0.221038818359375},{"x":-0.04168701171875,"y":0.0550537109375},{"x":0.07269287109375,"y":0.472686767578125},{"x":0.09564208984375,"y":0.515716552734375},{"x":0.191070556640625,"y":0.014373779296875},{"x":-0.040069580078125,"y":0.03533935546875},{"x":-0.01385498046875,"y":0.09661865234375},{"x":-0.043365478515625,"y":-0.050018310546875},{"x":-0.15679931640625,"y":-0.45147705078125}],"optimisedCameraToObject":{"translation":{"x":-0.04867072340088375,"y":-0.01832101838619833,"z":0.5053021167898529},"rotation":{"quaternion":{"W":0.9938371689272831,"X":0.10492779849425388,"Y":-0.001581974226781419,"Z":0.03571184844415032}}},"includeObservationInCalibration":true,"snapshotName":"img28.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img28.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":293.9643249511719,"y":379.8685302734375},{"x":326.1309509277344,"y":382.9114685058594},{"x":359.0419616699219,"y":386.30755615234375},{"x":391.7657165527344,"y":389.3065185546875},{"x":423.96441650390625,"y":392.71441650390625},{"x":456.6072692871094,"y":395.2980041503906},{"x":488.8177185058594,"y":398.8053894042969},{"x":291.1709289550781,"y":409.4529724121094},{"x":323.42169189453125,"y":413.0541687011719},{"x":355.9486083984375,"y":416.02252197265625},{"x":388.4119873046875,"y":419.1802062988281},{"x":419.7155456542969,"y":422.2720031738281},{"x":452.0560607910156,"y":425.2830810546875},{"x":483.7285461425781,"y":427.8988952636719},{"x":289.5106506347656,"y":438.3467712402344},{"x":320.8888244628906,"y":441.2348327636719},{"x":353.2174072265625,"y":444.31396484375},{"x":384.4458923339844,"y":447.1912536621094},{"x":415.91143798828125,"y":450.8494567871094},{"x":447.78594970703125,"y":453.34197998046875},{"x":478.94219970703125,"y":456.8750305175781},{"x":286.9893798828125,"y":466.89410400390625},{"x":318.2755432128906,"y":469.7911682128906},{"x":349.7681579589844,"y":472.8266296386719},{"x":381.0450134277344,"y":475.916015625},{"x":412.5104675292969,"y":478.4594421386719},{"x":443.8511962890625,"y":481.65386962890625},{"x":474.48040771484375,"y":484.1413879394531},{"x":285.24212646484375,"y":493.8400573730469},{"x":315.98162841796875,"y":496.9057922363281},{"x":346.90399169921875,"y":499.9557189941406},{"x":378.2687683105469,"y":502.46466064453125},{"x":408.74896240234375,"y":505.69659423828125},{"x":439.8577575683594,"y":508.07867431640625},{"x":469.9589538574219,"y":511.5660705566406},{"x":282.67169189453125,"y":520.44140625},{"x":314.0028991699219,"y":523.6378784179688},{"x":344.0594787597656,"y":526.4285278320312},{"x":374.728271484375,"y":529.2548828125},{"x":404.8978271484375,"y":532.0230712890625},{"x":436.1986999511719,"y":534.8216552734375},{"x":466.1737976074219,"y":538.3458251953125},{"x":281.0627136230469,"y":546.8153686523438},{"x":311.26043701171875,"y":549.5764770507812},{"x":341.60009765625,"y":552.7264404296875},{"x":371.8474426269531,"y":555.7198486328125},{"x":401.7217102050781,"y":557.9270629882812},{"x":431.73187255859375,"y":560.9755249023438},{"x":461.5691223144531,"y":564.0104370117188}],"reprojectionErrors":[{"x":-0.369415283203125,"y":-0.0040283203125},{"x":0.1552734375,"y":0.186004638671875},{"x":-0.116485595703125,"y":-0.00189208984375},{"x":-0.259368896484375,"y":0.18194580078125},{"x":0.058197021484375,"y":-0.06903076171875},{"x":-0.1392822265625,"y":0.477813720703125},{"x":0.0186767578125,"y":0.073883056640625},{"x":0.20086669921875,"y":0.184478759765625},{"x":0.202972412109375,"y":-0.251251220703125},{"x":-0.121551513671875,"y":-0.0804443359375},{"x":-0.4390869140625,"y":-0.125762939453125},{"x":0.340484619140625,"y":-0.132568359375},{"x":0.014373779296875,"y":-0.086517333984375},{"x":0.281494140625,"y":0.326385498046875},{"x":-0.299163818359375,"y":0.25750732421875},{"x":0.147369384765625,"y":0.46966552734375},{"x":-0.4053955078125,"y":0.463104248046875},{"x":0.087066650390625,"y":0.630157470703125},{"x":0.2816162109375,"y":-0.01239013671875},{"x":4.8828125E-4,"y":0.481536865234375},{"x":0.365020751953125,"y":-0.094757080078125},{"x":0.12237548828125,"y":-0.100921630859375},{"x":0.24273681640625,"y":0.03924560546875},{"x":0.109222412109375,"y":0.011993408203125},{"x":0.138214111328125,"y":-0.0986328125},{"x":-0.080413818359375,"y":0.30670166015625},{"x":-0.239105224609375,"y":0.03057861328125},{"x":0.24322509765625,"y":0.43048095703125},{"x":-0.171600341796875,"y":0.391204833984375},{"x":0.086822509765625,"y":0.301788330078125},{"x":0.11639404296875,"y":0.19793701171875},{"x":-0.34814453125,"y":0.6043701171875},{"x":0.0146484375,"y":0.256622314453125},{"x":-0.314117431640625,"y":0.727142333984375},{"x":0.296234130859375,"y":0.060272216796875},{"x":0.4140625,"y":0.50286865234375},{"x":-0.31854248046875,"y":0.22381591796875},{"x":0.178863525390625,"y":0.31915283203125},{"x":0.013916015625,"y":0.34698486328125},{"x":0.29254150390625,"y":0.400634765625},{"x":-0.621246337890625,"y":0.3912353515625},{"x":-0.27581787109375,"y":-0.37689208984375},{"x":0.092803955078125,"y":0.1414794921875},{"x":0.10333251953125,"y":0.2408447265625},{"x":-0.071380615234375,"y":-0.0811767578125},{"x":-0.202423095703125,"y":-0.27960205078125},{"x":-0.01446533203125,"y":0.27490234375},{"x":-0.021759033203125,"y":-0.045654296875},{"x":0.07916259765625,"y":-0.38677978515625}],"optimisedCameraToObject":{"translation":{"x":-0.08323945884560988,"y":0.037952487497259275,"z":0.5223705566148297},"rotation":{"quaternion":{"W":0.9880823354844781,"X":0.1452679174364017,"Y":-0.002552702990465036,"Z":0.05083319953212273}}},"includeObservationInCalibration":true,"snapshotName":"img29.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img29.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.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.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}],"locationInImageSpace":[{"x":288.7093200683594,"y":405.2923889160156},{"x":321.8953857421875,"y":407.308837890625},{"x":354.2223815917969,"y":409.8620910644531},{"x":387.0834045410156,"y":411.7196350097656},{"x":419.14068603515625,"y":414.048828125},{"x":255.7470703125,"y":432.5801086425781},{"x":288.0283203125,"y":435.0072326660156},{"x":320.53790283203125,"y":437.1368713378906},{"x":352.4447021484375,"y":439.76971435546875},{"x":384.74853515625,"y":441.60687255859375},{"x":417.1012268066406,"y":443.6098937988281},{"x":223.14451599121094,"y":459.6646423339844},{"x":254.5936279296875,"y":461.3688049316406},{"x":287.2936096191406,"y":463.8106384277344},{"x":318.9393615722656,"y":465.9602966308594},{"x":350.30810546875,"y":468.5065002441406},{"x":382.5262451171875,"y":470.4820556640625},{"x":413.53948974609375,"y":472.8867492675781},{"x":222.85873413085938,"y":487.38092041015625},{"x":254.62384033203125,"y":489.91339111328125},{"x":285.91961669921875,"y":492.1321105957031},{"x":317.6078186035156,"y":494.7411804199219},{"x":348.7239074707031,"y":496.8511657714844},{"x":380.76287841796875,"y":499.033935546875},{"x":411.5990295410156,"y":501.11663818359375},{"x":223.03248596191406,"y":514.983154296875},{"x":253.81771850585938,"y":517.20361328125},{"x":285.162353515625,"y":519.6964721679688},{"x":316.22930908203125,"y":521.91552734375},{"x":346.8365173339844,"y":524.2481079101562},{"x":377.9671325683594,"y":526.1317749023438},{"x":409.445556640625,"y":528.7875366210938},{"x":222.24493408203125,"y":541.6229248046875},{"x":252.81588745117188,"y":544.4747314453125},{"x":345.16265869140625,"y":551.1740112304688},{"x":376.01214599609375,"y":553.7467651367188},{"x":406.6285705566406,"y":556.26025390625},{"x":222.1927947998047,"y":568.5065307617188},{"x":252.18162536621094,"y":570.391357421875}],"reprojectionErrors":[{"x":0.27117919921875,"y":-0.1263427734375},{"x":-0.264129638671875,"y":0.199737548828125},{"x":0.083770751953125,"y":-0.029510498046875},{"x":-0.084716796875,"y":0.41796875},{"x":0.5616455078125,"y":0.374359130859375},{"x":-0.079376220703125,"y":0.0364990234375},{"x":-0.14776611328125,"y":-0.04779052734375},{"x":-0.41448974609375,"y":0.1456298828125},{"x":-0.054779052734375,"y":-0.184356689453125},{"x":-0.074737548828125,"y":0.2606201171875},{"x":-0.132568359375,"y":0.5185546875},{"x":0.0744781494140625,"y":-0.33221435546875},{"x":0.4040985107421875,"y":0.3096923828125},{"x":-0.481597900390625,"y":0.19305419921875},{"x":-0.28369140625,"y":0.347137451171875},{"x":0.2144775390625,"y":0.082855224609375},{"x":-0.119659423828125,"y":0.366851806640625},{"x":0.761962890625,"y":0.198944091796875},{"x":0.1016082763671875,"y":0.3040771484375},{"x":-0.274169921875,"y":0.1016845703125},{"x":-0.14581298828125,"y":0.1905517578125},{"x":-0.38104248046875,"y":-0.1339111328125},{"x":-0.02130126953125,"y":0.01727294921875},{"x":-0.56768798828125,"y":0.07183837890625},{"x":0.099517822265625,"y":0.202117919921875},{"x":-0.317779541015625,"y":0.35205078125},{"x":-0.0949249267578125,"y":0.44561767578125},{"x":-0.3973388671875,"y":0.2427978515625},{"x":-0.393798828125,"y":0.28936767578125},{"x":0.091888427734375,"y":0.19744873046875},{"x":0.07073974609375,"y":0.5291748046875},{"x":-0.28759765625,"y":0.06304931640625},{"x":0.2367095947265625,"y":0.6820068359375},{"x":0.300537109375,"y":0.128173828125},{"x":0.035980224609375,"y":0.168701171875},{"x":-0.079254150390625,"y":-0.2103271484375},{"x":0.04913330078125,"y":-0.55718994140625},{"x":0.06793212890625,"y":0.10870361328125},{"x":0.3482818603515625,"y":0.505859375}],"optimisedCameraToObject":{"translation":{"x":-0.13858952939981845,"y":0.05462210397925629,"z":0.5252639846479085},"rotation":{"quaternion":{"W":0.9903458037998749,"X":0.1340354263735569,"Y":0.008170477058724467,"Z":0.03439384650589897}}},"includeObservationInCalibration":true,"snapshotName":"img30.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img30.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 13636f1..d2043d9 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -8,19 +8,13 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; -import edu.wpi.first.math.MatBuilder; -import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.numbers.N8; import edu.wpi.first.math.util.Units; import java.util.Optional; import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; -import org.team2342.frc.subsystems.vision.Vision.CameraParameters; +import org.team2342.lib.util.CameraParameters; public final class Constants { public static final Mode CURRENT_MODE = Mode.SIM; @@ -61,33 +55,11 @@ public static final class VisionConstants { public static final AprilTagFieldLayout TAG_LAYOUT = AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded); - public static final Matrix cameraMatrix = - MatBuilder.fill( - Nat.N3(), - Nat.N3(), - 680.3518437477294, - 0.0, - 393.34429560711095, - 0.0, - 681.5148816063638, - 304.5111454902841, - 0.0, - 0.0, - 1.0); - public static final Matrix distCoeffs = - MatBuilder.fill( - Nat.N8(), - Nat.N1(), - 0.04913279370181987, - -0.08080811604393605, - 0.0012713783068216294, - -9.086414571538155E-4, - 0.03813939624862079, - -0.002083234186226857, - 0.003667258530403619, - -0.0014957440403602612); - public static final CameraParameters PARAMETERS = - new CameraParameters(800, 600, cameraMatrix, distCoeffs); + public static final CameraParameters LEFT_PARAMETERS = + CameraParameters.loadFromName(LEFT_CAMERA_NAME, 800, 600); + public static final CameraParameters RIGHT_PARAMETERS = + CameraParameters.loadFromName(RIGHT_CAMERA_NAME, 800, 600); + public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 937985b..2f114b6 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -66,14 +66,12 @@ public RobotContainer() { drive::addVisionMeasurement, drive::getTimestampedHeading, new VisionIOPhoton( - VisionConstants.RIGHT_CAMERA_NAME, - VisionConstants.PARAMETERS, + VisionConstants.RIGHT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_RIGHT_TRANSFORM), new VisionIOPhoton( - VisionConstants.LEFT_CAMERA_NAME, - VisionConstants.PARAMETERS, + VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_LEFT_TRANSFORM)); @@ -94,15 +92,13 @@ public RobotContainer() { drive::addVisionMeasurement, drive::getTimestampedHeading, new VisionIOSim( - VisionConstants.RIGHT_CAMERA_NAME, - VisionConstants.PARAMETERS, + VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_RIGHT_TRANSFORM, drive::getRawOdometryPose), new VisionIOSim( - VisionConstants.LEFT_CAMERA_NAME, - VisionConstants.PARAMETERS, + VisionConstants.RIGHT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, VisionConstants.FRONT_LEFT_TRANSFORM, diff --git a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java index 4e3a367..12a9419 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java @@ -14,7 +14,6 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.numbers.N8; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -195,7 +194,4 @@ public void accept( double timestampSeconds, Matrix visionMeasurementStdDevs); } - - public record CameraParameters( - int resWidth, int resHeight, Matrix cameraMatrix, Matrix distCoeffs) {} } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java index f5ce1f7..a3c289c 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java @@ -22,19 +22,18 @@ import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.photonvision.targeting.PhotonTrackedTarget; import org.team2342.frc.Constants; -import org.team2342.frc.subsystems.vision.Vision.CameraParameters; +import org.team2342.lib.util.CameraParameters; import org.team2342.lib.util.Timestamped; /** IO implementation for real PhotonVision hardware. */ public class VisionIOPhoton implements VisionIO { protected final PhotonCamera camera; + protected final CameraParameters parameters; protected final Transform3d robotToCamera; private final PhotonPoseEstimator poseEstimator; private final PoseStrategy primaryStrategy; - private final CameraParameters parameters; - private boolean hasEnabled = false; // TODO: AllianceUtils @@ -45,12 +44,11 @@ public class VisionIOPhoton implements VisionIO { * @param robotToCamera The 3D position of the camera relative to the robot. */ public VisionIOPhoton( - String name, CameraParameters parameters, PoseStrategy primaryStrategy, PoseStrategy disabledStrategy, Transform3d robotToCamera) { - camera = new PhotonCamera(name); + camera = new PhotonCamera(parameters.getCameraName()); this.robotToCamera = robotToCamera; this.parameters = parameters; poseEstimator = @@ -85,8 +83,8 @@ public void updateInputs(VisionIOInputs inputs, Timestamped heading) Optional optional = poseEstimator.update( result, - Optional.ofNullable(parameters.cameraMatrix()), - Optional.ofNullable(parameters.distCoeffs()), + Optional.of(parameters.getCameraMatrix()), + Optional.of(parameters.getDistCoeffs()), Constants.VisionConstants.CONSTRAINED_SOLVEPNP_PARAMETERS); if (optional.isEmpty()) { continue; diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java index 6a651da..c81b487 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java @@ -15,7 +15,7 @@ import org.photonvision.simulation.SimCameraProperties; import org.photonvision.simulation.VisionSystemSim; import org.team2342.frc.Constants.VisionConstants; -import org.team2342.frc.subsystems.vision.Vision.CameraParameters; +import org.team2342.lib.util.CameraParameters; import org.team2342.lib.util.Timestamped; /** IO implementation for physics sim using PhotonVision simulator. */ @@ -32,13 +32,12 @@ public class VisionIOSim extends VisionIOPhoton { * @param poseSupplier Supplier for the robot pose to use in simulation. */ public VisionIOSim( - String name, CameraParameters parameters, PoseStrategy primaryStrategy, PoseStrategy disabledStrategy, Transform3d robotToCamera, Supplier poseSupplier) { - super(name, parameters, primaryStrategy, disabledStrategy, robotToCamera); + super(parameters, primaryStrategy, disabledStrategy, robotToCamera); this.poseSupplier = poseSupplier; if (visionSim == null) { @@ -49,12 +48,12 @@ public VisionIOSim( // Add sim camera SimCameraProperties properties = new SimCameraProperties(); properties.setCalibration( - parameters.resWidth(), - parameters.resHeight(), - parameters.cameraMatrix(), - parameters.distCoeffs()); - properties.setCalibError(0.02, 0.05); - properties.setFPS(60); + parameters.getResWidth(), + parameters.getResHeight(), + parameters.getCameraMatrix(), + parameters.getDistCoeffs()); + properties.setCalibError(parameters.getAvgErrorPx(), parameters.getErrorStdDevPx()); + properties.setFPS(60.0); properties.setAvgLatencyMs(35); properties.setLatencyStdDevMs(7); diff --git a/src/main/java/org/team2342/lib/util/CameraParameters.java b/src/main/java/org/team2342/lib/util/CameraParameters.java new file mode 100644 index 0000000..a7c62ad --- /dev/null +++ b/src/main/java/org/team2342/lib/util/CameraParameters.java @@ -0,0 +1,161 @@ +// Copyright (c) 2025 Team 2342 +// https://github.com/FRCTeamPhoenix +// +// This source code is licensed under the MIT License. +// See the LICENSE file in the root directory of this project. + +package org.team2342.lib.util; + +import com.fasterxml.jackson.databind.ObjectMapper; +import edu.wpi.first.math.MatBuilder; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.Nat; +import edu.wpi.first.math.VecBuilder; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.math.numbers.N8; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.Filesystem; +import java.io.IOException; +import java.nio.file.Path; +import java.util.Arrays; +import lombok.Getter; +import lombok.Setter; + +public class CameraParameters { + + @Getter @Setter private String cameraName; + @Getter @Setter private int resWidth, resHeight; + @Getter @Setter private Matrix cameraMatrix; + @Getter @Setter private Matrix distCoeffs; + @Getter @Setter private double avgErrorPx; + @Getter @Setter private double errorStdDevPx; + + public CameraParameters( + String cameraName, + int resWidth, + int resHeight, + double avgErrorPx, + double errorStdDevPx, + Matrix cameraMatrix, + Matrix distCoeffs) { + this.cameraName = cameraName; + this.resWidth = resWidth; + this.resHeight = resHeight; + this.avgErrorPx = avgErrorPx; + this.errorStdDevPx = errorStdDevPx; + this.cameraMatrix = cameraMatrix; + this.distCoeffs = distCoeffs; + } + + public CameraParameters(String cameraName, int resWidth, int resHeight) { + this(cameraName, resWidth, resHeight, 0.02, 0.05, Rotation2d.kCCW_90deg); + } + + public CameraParameters( + String cameraName, + int resWidth, + int resHeight, + double avgErrorPx, + double errorStdDevPx, + Rotation2d fovDiag) { + this.cameraName = cameraName; + this.resWidth = resWidth; + this.resHeight = resHeight; + this.avgErrorPx = avgErrorPx; + this.errorStdDevPx = errorStdDevPx; + + if (fovDiag.getDegrees() < 1 || fovDiag.getDegrees() > 179) { + fovDiag = Rotation2d.fromDegrees(MathUtil.clamp(fovDiag.getDegrees(), 1, 179)); + DriverStation.reportError( + "Requested invalid FOV! Clamping between (1, 179) degrees...", false); + } + double resDiag = Math.hypot(resWidth, resHeight); + double diagRatio = Math.tan(fovDiag.getRadians() / 2); + var fovWidth = new Rotation2d(Math.atan(diagRatio * (resWidth / resDiag)) * 2); + var fovHeight = new Rotation2d(Math.atan(diagRatio * (resHeight / resDiag)) * 2); + + // assume no distortion + distCoeffs = VecBuilder.fill(0, 0, 0, 0, 0, 0, 0, 0); + + // assume centered principal point (pixels) + double cx = resWidth / 2.0 - 0.5; + double cy = resHeight / 2.0 - 0.5; + + // use given fov to determine focal point (pixels) + double fx = cx / Math.tan(fovWidth.getRadians() / 2.0); + double fy = cy / Math.tan(fovHeight.getRadians() / 2.0); + + // create camera intrinsics matrix + cameraMatrix = MatBuilder.fill(Nat.N3(), Nat.N3(), fx, 0, cx, 0, fy, cy, 0, 0, 1); + } + + public CameraParameters(String cameraName, int resWidth, int resHeight, Path path) + throws IOException { + this.cameraName = cameraName; + var mapper = new ObjectMapper(); + var json = mapper.readTree(path.toFile()); + // json = json.get("calibrations"); + boolean success = false; + try { + for (int i = 0; i < json.size() && !success; i++) { + // check if this calibration entry is our desired resolution + int jsonWidth = json.get("resolution").get("width").asInt(); + int jsonHeight = json.get("resolution").get("height").asInt(); + if (jsonWidth != resWidth || jsonHeight != resHeight) continue; + // get the relevant calibration values + var jsonIntrinsicsNode = json.get("cameraIntrinsics").get("data"); + double[] jsonIntrinsics = new double[jsonIntrinsicsNode.size()]; + for (int j = 0; j < jsonIntrinsicsNode.size(); j++) { + jsonIntrinsics[j] = jsonIntrinsicsNode.get(j).asDouble(); + } + var jsonDistortNode = json.get("distCoeffs").get("data"); + double[] jsonDistortion = new double[8]; + Arrays.fill(jsonDistortion, 0); + for (int j = 0; j < jsonDistortNode.size(); j++) { + jsonDistortion[j] = jsonDistortNode.get(j).asDouble(); + } + + // not working + // var jsonViewErrors = json.get("perViewErrors"); + // double jsonAvgError = 0; + // for (int j = 0; j < jsonViewErrors.size(); j++) { + // jsonAvgError += jsonViewErrors.get(j).asDouble(); + // } + // jsonAvgError /= jsonViewErrors.size(); + // double jsonErrorStdDev = json.get("standardDeviation").asDouble(); + + // assign the read JSON values to this CameraProperties + this.resWidth = jsonWidth; + this.resHeight = jsonHeight; + this.cameraMatrix = MatBuilder.fill(Nat.N3(), Nat.N3(), jsonIntrinsics); + this.distCoeffs = MatBuilder.fill(Nat.N8(), Nat.N1(), jsonDistortion); + avgErrorPx = 0.02; // jsonAvgError; + errorStdDevPx = 0.05; // jsonErrorStdDev; + success = true; + } + } catch (Exception e) { + throw new IOException("Invalid calibration JSON"); + } + if (!success) throw new IOException("Requested resolution not found in calibration"); + } + + public static CameraParameters loadFromName(String cameraName, int resWidth, int resHeight) { + try { + return new CameraParameters( + cameraName, + resWidth, + resHeight, + Filesystem.getDeployDirectory() + .toPath() + .resolve("calibrations/" + cameraName + "_" + resWidth + ".json")); + } catch (Exception e) { + System.out.println(e); + DriverStation.reportError( + "Error while loading camera " + cameraName + ". Resorting to basic parameters", false); + return new CameraParameters(cameraName, resWidth, resHeight); + } + } +} From 5ec674354b01eece32a88133d274c95019c9979c Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Mon, 12 Jan 2026 09:07:57 -0500 Subject: [PATCH 5/7] modifying parameters --- src/main/java/org/team2342/frc/Constants.java | 11 ++++------- .../java/org/team2342/frc/RobotContainer.java | 9 ++------- .../org/team2342/frc/subsystems/drive/Drive.java | 1 + .../team2342/frc/subsystems/vision/Vision.java | 2 +- .../frc/subsystems/vision/VisionIOPhoton.java | 15 +++++++-------- .../frc/subsystems/vision/VisionIOSim.java | 7 ++----- .../org/team2342/lib/util/CameraParameters.java | 9 ++++++++- .../java/org/team2342/lib/util/Timestamped.java | 2 +- 8 files changed, 26 insertions(+), 30 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index c9cb5f5..019d915 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -10,8 +10,6 @@ import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; -import java.util.Optional; -import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; import org.team2342.lib.util.CameraParameters; public final class Constants { @@ -50,12 +48,11 @@ public static final class VisionConstants { new Rotation3d(0, 0.0, Units.degreesToRadians(35))); public static final CameraParameters LEFT_PARAMETERS = - CameraParameters.loadFromName(LEFT_CAMERA_NAME, 800, 600); + CameraParameters.loadFromName(LEFT_CAMERA_NAME, 800, 600) + .withTransform(FRONT_LEFT_TRANSFORM); public static final CameraParameters RIGHT_PARAMETERS = - CameraParameters.loadFromName(RIGHT_CAMERA_NAME, 800, 600); - - public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = - Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); + CameraParameters.loadFromName(RIGHT_CAMERA_NAME, 800, 600) + .withTransform(FRONT_RIGHT_TRANSFORM); // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 385d207..1a53f99 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -12,7 +12,6 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform2d; -import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; @@ -73,13 +72,11 @@ public RobotContainer() { new VisionIOPhoton( VisionConstants.RIGHT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, - PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, - new Transform3d()), + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR), new VisionIOPhoton( VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, - PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, - new Transform3d())); + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); break; @@ -100,13 +97,11 @@ public RobotContainer() { VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, - VisionConstants.FRONT_RIGHT_TRANSFORM, drive::getRawOdometryPose), new VisionIOSim( VisionConstants.RIGHT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, - VisionConstants.FRONT_LEFT_TRANSFORM, drive::getRawOdometryPose)); break; diff --git a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java index f8d24fd..3733381 100644 --- a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java +++ b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java @@ -32,6 +32,7 @@ import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; diff --git a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java index 96989f2..be01292 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java @@ -24,8 +24,8 @@ import org.team2342.frc.Constants.VisionConstants; import org.team2342.frc.subsystems.vision.VisionIO.PoseObservationType; import org.team2342.lib.logging.ExecutionLogger; -import org.team2342.lib.util.Timestamped; import org.team2342.lib.util.AllianceUtils; +import org.team2342.lib.util.Timestamped; public class Vision extends SubsystemBase { private final VisionConsumer consumer; diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java index e86edf8..3183f07 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java @@ -19,12 +19,11 @@ import org.photonvision.EstimatedRobotPose; import org.photonvision.PhotonCamera; import org.photonvision.PhotonPoseEstimator; +import org.photonvision.PhotonPoseEstimator.ConstrainedSolvepnpParams; import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.photonvision.targeting.PhotonTrackedTarget; -import org.team2342.frc.Constants; import org.team2342.lib.util.CameraParameters; import org.team2342.lib.util.Timestamped; -import org.team2342.lib.util.AllianceUtils; /** IO implementation for real PhotonVision hardware. */ public class VisionIOPhoton implements VisionIO { @@ -37,6 +36,9 @@ public class VisionIOPhoton implements VisionIO { private boolean hasEnabled = false; + public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = + Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); + // TODO: AllianceUtils /** * Creates a new VisionIOPhotonVision. @@ -45,12 +47,9 @@ public class VisionIOPhoton implements VisionIO { * @param robotToCamera The 3D position of the camera relative to the robot. */ public VisionIOPhoton( - CameraParameters parameters, - PoseStrategy primaryStrategy, - PoseStrategy disabledStrategy, - Transform3d robotToCamera) { + CameraParameters parameters, PoseStrategy primaryStrategy, PoseStrategy disabledStrategy) { camera = new PhotonCamera(parameters.getCameraName()); - this.robotToCamera = robotToCamera; + this.robotToCamera = parameters.getTransform(); this.parameters = parameters; poseEstimator = new PhotonPoseEstimator( @@ -86,7 +85,7 @@ public void updateInputs(VisionIOInputs inputs, Timestamped heading) result, Optional.of(parameters.getCameraMatrix()), Optional.of(parameters.getDistCoeffs()), - Constants.VisionConstants.CONSTRAINED_SOLVEPNP_PARAMETERS); + CONSTRAINED_SOLVEPNP_PARAMETERS); if (optional.isEmpty()) { continue; } diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java index b82d588..26647de 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOSim.java @@ -8,16 +8,14 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Transform3d; import java.util.function.Supplier; import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.photonvision.simulation.PhotonCameraSim; import org.photonvision.simulation.SimCameraProperties; import org.photonvision.simulation.VisionSystemSim; -import org.team2342.frc.Constants.VisionConstants; +import org.team2342.lib.util.AllianceUtils; import org.team2342.lib.util.CameraParameters; import org.team2342.lib.util.Timestamped; -import org.team2342.lib.util.AllianceUtils; /** IO implementation for physics sim using PhotonVision simulator. */ public class VisionIOSim extends VisionIOPhoton { @@ -36,9 +34,8 @@ public VisionIOSim( CameraParameters parameters, PoseStrategy primaryStrategy, PoseStrategy disabledStrategy, - Transform3d robotToCamera, Supplier poseSupplier) { - super(parameters, primaryStrategy, disabledStrategy, robotToCamera); + super(parameters, primaryStrategy, disabledStrategy); this.poseSupplier = poseSupplier; if (visionSim == null) { diff --git a/src/main/java/org/team2342/lib/util/CameraParameters.java b/src/main/java/org/team2342/lib/util/CameraParameters.java index a7c62ad..dde8f0b 100644 --- a/src/main/java/org/team2342/lib/util/CameraParameters.java +++ b/src/main/java/org/team2342/lib/util/CameraParameters.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. @@ -13,6 +13,7 @@ import edu.wpi.first.math.Nat; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import edu.wpi.first.math.numbers.N8; @@ -32,6 +33,7 @@ public class CameraParameters { @Getter @Setter private Matrix distCoeffs; @Getter @Setter private double avgErrorPx; @Getter @Setter private double errorStdDevPx; + @Getter @Setter private Transform3d transform; public CameraParameters( String cameraName, @@ -158,4 +160,9 @@ public static CameraParameters loadFromName(String cameraName, int resWidth, int return new CameraParameters(cameraName, resWidth, resHeight); } } + + public CameraParameters withTransform(Transform3d transform) { + this.transform = transform; + return this; + } } diff --git a/src/main/java/org/team2342/lib/util/Timestamped.java b/src/main/java/org/team2342/lib/util/Timestamped.java index d882ff3..2b8f3e1 100644 --- a/src/main/java/org/team2342/lib/util/Timestamped.java +++ b/src/main/java/org/team2342/lib/util/Timestamped.java @@ -1,4 +1,4 @@ -// Copyright (c) 2025 Team 2342 +// Copyright (c) 2026 Team 2342 // https://github.com/FRCTeamPhoenix // // This source code is licensed under the MIT License. From 8386098dee292dd43cfb6e8a88112f8475e13102 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Sun, 18 Jan 2026 12:45:46 -0500 Subject: [PATCH 6/7] testing --- build.gradle | 2 +- .../deploy/calibrations/left_arducam_800.json | 2 +- .../calibrations/right_arducam_800.json | 1 - src/main/java/org/team2342/frc/Constants.java | 27 +++++-------------- src/main/java/org/team2342/frc/Robot.java | 4 ++- .../java/org/team2342/frc/RobotContainer.java | 16 +++-------- .../frc/subsystems/vision/VisionIOPhoton.java | 1 - ...rLib.json => PathplannerLib-2026.1.2.json} | 8 +++--- vendordeps/REVLib.json | 18 ++++++------- ....0.0-beta1.json => ReduxLib-2026.1.1.json} | 12 ++++----- vendordeps/photonlib.json | 12 ++++----- 11 files changed, 41 insertions(+), 62 deletions(-) delete mode 100644 src/main/deploy/calibrations/right_arducam_800.json rename vendordeps/{PathplannerLib.json => PathplannerLib-2026.1.2.json} (87%) rename vendordeps/{ReduxLib-2026.0.0-beta1.json => ReduxLib-2026.1.1.json} (87%) diff --git a/build.gradle b/build.gradle index 6d523e9..3d13dc0 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2026.1.1" + id "edu.wpi.first.GradleRIO" version "2026.2.1" id "com.peterabeles.gversion" version "1.10" id "com.diffplug.spotless" version "6.12.0" id "io.freefair.lombok" version "8.4" diff --git a/src/main/deploy/calibrations/left_arducam_800.json b/src/main/deploy/calibrations/left_arducam_800.json index dce0ae1..0e4edc7 100644 --- a/src/main/deploy/calibrations/left_arducam_800.json +++ b/src/main/deploy/calibrations/left_arducam_800.json @@ -1 +1 @@ -{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[680.3518437477294,0.0,393.34429560711095,0.0,681.5148816063638,304.5111454902841,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04913279370181987,-0.08080811604393605,0.0012713783068216294,-9.086414571538155E-4,0.03813939624862079,-0.002083234186226857,0.003667258530403619,-0.0014957440403602612]},"calobjectWarp":[-2.4222652881449006E-4,-7.403314167453361E-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.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.63787841796875,"y":201.96435546875},{"x":420.0296936035156,"y":203.2669219970703},{"x":444.2115783691406,"y":204.21347045898438},{"x":468.8716735839844,"y":205.87741088867188},{"x":492.6279296875,"y":206.98814392089844},{"x":516.905517578125,"y":208.358642578125},{"x":540.6669921875,"y":209.6805419921875},{"x":394.31170654296875,"y":226.8882293701172},{"x":418.8793640136719,"y":227.9027099609375},{"x":442.83978271484375,"y":228.966064453125},{"x":467.054931640625,"y":230.47303771972656},{"x":490.9638366699219,"y":231.596435546875},{"x":514.9796142578125,"y":232.9580078125},{"x":538.2432250976562,"y":234.12216186523438},{"x":392.8952941894531,"y":251.2106170654297},{"x":417.048095703125,"y":252.2500457763672},{"x":441.32562255859375,"y":253.8323516845703},{"x":465.17327880859375,"y":254.6101531982422},{"x":489.1075439453125,"y":255.8332977294922},{"x":512.9839477539062,"y":257.06500244140625},{"x":536.1762084960938,"y":258.12213134765625},{"x":391.6473693847656,"y":275.9429016113281},{"x":415.8117370605469,"y":276.5908508300781},{"x":439.90936279296875,"y":277.9654541015625},{"x":463.9397277832031,"y":279.0257568359375},{"x":487.305419921875,"y":279.9642639160156},{"x":510.98260498046875,"y":281.11273193359375},{"x":534.46923828125,"y":282.29754638671875},{"x":390.2811279296875,"y":299.2279052734375},{"x":414.2469177246094,"y":300.66754150390625},{"x":438.0099182128906,"y":301.4851989746094},{"x":462.0777587890625,"y":302.62823486328125},{"x":485.6961364746094,"y":303.857666015625},{"x":509.1346740722656,"y":304.3945007324219},{"x":532.2939453125,"y":305.8572082519531},{"x":388.7101745605469,"y":322.96112060546875},{"x":412.8590087890625,"y":324.3318786621094},{"x":436.7467041015625,"y":325.2496643066406},{"x":460.26776123046875,"y":326.05523681640625},{"x":483.86956787109375,"y":327.3586730957031},{"x":507.3291320800781,"y":328.107666015625},{"x":530.8265991210938,"y":329.02960205078125},{"x":387.98370361328125,"y":346.7546691894531},{"x":411.718017578125,"y":347.8789367675781},{"x":434.97021484375,"y":348.78057861328125},{"x":458.7391357421875,"y":349.7117614746094},{"x":482.2115173339844,"y":350.461669921875},{"x":505.65484619140625,"y":351.5047912597656},{"x":528.6858520507812,"y":352.2821350097656}],"reprojectionErrors":[{"x":-0.078582763671875,"y":-0.1130523681640625},{"x":0.03668212890625,"y":-0.0861358642578125},{"x":0.233642578125,"y":0.289947509765625},{"x":-0.178924560546875,"y":-0.0583953857421875},{"x":0.17803955078125,"y":0.1392822265625},{"x":-0.12353515625,"y":0.069854736328125},{"x":-0.04901123046875,"y":0.0415191650390625},{"x":-0.070159912109375,"y":-0.2250518798828125},{"x":-0.255615234375,"y":0.02093505859375},{"x":0.039306640625,"y":0.2102203369140625},{"x":-0.0504150390625,"y":-0.052093505859375},{"x":0.03326416015625,"y":0.06103515625},{"x":-0.12567138671875,"y":-0.0722808837890625},{"x":0.3289794921875,"y":-0.016571044921875},{"x":0.041473388671875,"y":0.0047760009765625},{"x":0.146881103515625,"y":0.1581573486328125},{"x":0.002044677734375,"y":-0.240142822265625},{"x":0.1585693359375,"y":0.157135009765625},{"x":0.097015380859375,"y":0.1000213623046875},{"x":-0.04095458984375,"y":0.025177001953125},{"x":0.3680419921875,"y":0.115631103515625},{"x":-0.00250244140625,"y":-0.43212890625},{"x":-0.031829833984375,"y":0.04638671875},{"x":-0.11859130859375,"y":-0.211517333984375},{"x":-0.265228271484375,"y":-0.164947509765625},{"x":0.122772216796875,"y":-0.00653076171875},{"x":0.06634521484375,"y":-0.068145751953125},{"x":0.0648193359375,"y":-0.17626953125},{"x":0.08453369140625,"y":0.324188232421875},{"x":0.1314697265625,"y":-0.054046630859375},{"x":0.25836181640625,"y":0.179046630859375},{"x":-0.045379638671875,"y":0.07598876953125},{"x":-0.028350830078125,"y":-0.124298095703125},{"x":0.03704833984375,"y":0.357086181640625},{"x":0.2474365234375,"y":-0.098419189453125},{"x":0.388885498046875,"y":0.381011962890625},{"x":0.131317138671875,"y":0.00787353515625},{"x":0.013336181640625,"y":0.076141357421875},{"x":0.137542724609375,"y":0.244964599609375},{"x":0.053680419921875,"y":-0.095794677734375},{"x":-0.018035888671875,"y":0.106109619140625},{"x":-0.260498046875,"y":0.12322998046875},{"x":-0.1387939453125,"y":0.12890625},{"x":-0.102508544921875,"y":-0.06024169921875},{"x":0.295684814453125,"y":-0.03924560546875},{"x":0.05401611328125,"y":-0.060333251953125},{"x":-0.017120361328125,"y":0.0872802734375},{"x":-0.18792724609375,"y":-0.070953369140625},{"x":-0.077880859375,"y":0.02392578125}],"optimisedCameraToObject":{"translation":{"x":-0.021683619027386893,"y":-0.13177694641447624,"z":0.6954322613892415},"rotation":{"quaternion":{"W":0.9963415936377188,"X":0.07429111312104363,"Y":-0.03464091969580141,"Z":0.024171594513314607}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":545.0081176757812,"y":214.97610473632812},{"x":567.103515625,"y":216.0049591064453},{"x":589.0089111328125,"y":216.98973083496094},{"x":610.510009765625,"y":218.22630310058594},{"x":631.96826171875,"y":219.06700134277344},{"x":653.1405029296875,"y":220.07257080078125},{"x":674.0646362304688,"y":221.20545959472656},{"x":543.9988403320312,"y":238.06126403808594},{"x":565.9149780273438,"y":239.13587951660156},{"x":587.8931884765625,"y":239.9783935546875},{"x":609.7720336914062,"y":240.8497772216797},{"x":631.0768432617188,"y":241.94493103027344},{"x":652.2105712890625,"y":242.7381134033203},{"x":672.8532104492188,"y":243.63467407226562},{"x":542.92822265625,"y":261.2977294921875},{"x":565.1015625,"y":262.0004577636719},{"x":586.6165161132812,"y":263.18701171875},{"x":608.23974609375,"y":263.8254699707031},{"x":629.5731201171875,"y":264.30181884765625},{"x":651.0245971679688,"y":265.15216064453125},{"x":671.7772216796875,"y":266.10601806640625},{"x":542.0488891601562,"y":284.6033935546875},{"x":564.0,"y":285.24639892578125},{"x":585.701904296875,"y":285.86431884765625},{"x":607.5843505859375,"y":286.44683837890625},{"x":629.022705078125,"y":287.1971740722656},{"x":650.05859375,"y":287.9716796875},{"x":671.0332641601562,"y":288.6597595214844},{"x":540.9203491210938,"y":307.23004150390625},{"x":562.9186401367188,"y":307.91412353515625},{"x":584.7335205078125,"y":308.21905517578125},{"x":606.27001953125,"y":309.10003662109375},{"x":627.8847045898438,"y":309.7110900878906},{"x":648.9175415039062,"y":310.220703125},{"x":669.8855590820312,"y":310.5852966308594},{"x":540.0347290039062,"y":330.3905029296875},{"x":561.883056640625,"y":331.00128173828125},{"x":583.7084350585938,"y":331.28564453125},{"x":605.1730346679688,"y":331.8525695800781},{"x":626.6658935546875,"y":332.0289001464844},{"x":647.9277954101562,"y":333.0074462890625},{"x":668.8612060546875,"y":333.46392822265625},{"x":538.8889770507812,"y":353.0419006347656},{"x":561.0779418945312,"y":353.19757080078125},{"x":582.8048706054688,"y":353.9272155761719},{"x":604.15380859375,"y":354.31658935546875},{"x":625.7700805664062,"y":354.94219970703125},{"x":647.063720703125,"y":355.2154541015625},{"x":667.9808959960938,"y":355.6434631347656}],"reprojectionErrors":[{"x":-0.07733154296875,"y":-0.0243377685546875},{"x":-0.07965087890625,"y":-0.0109710693359375},{"x":-0.1033935546875,"y":0.040252685546875},{"x":0.06512451171875,"y":-0.166656494140625},{"x":0.06402587890625,"y":0.0159149169921875},{"x":0.1361083984375,"y":0.02716064453125},{"x":0.24310302734375,"y":-0.0954437255859375},{"x":-0.0216064453125,"y":0.069305419921875},{"x":0.1318359375,"y":-0.06781005859375},{"x":0.0123291015625,"y":0.0206756591796875},{"x":-0.21929931640625,"y":0.0737457275390625},{"x":-0.08880615234375,"y":-0.1035614013671875},{"x":4.2724609375E-4,"y":0.0144500732421875},{"x":0.3680419921875,"y":0.022369384765625},{"x":0.093994140625,"y":-0.046478271484375},{"x":-0.03350830078125,"y":0.084075927734375},{"x":0.28704833984375,"y":-0.27593994140625},{"x":0.288330078125,"y":-0.09466552734375},{"x":0.36810302734375,"y":0.241912841796875},{"x":0.117919921875,"y":0.197662353515625},{"x":0.35443115234375,"y":0.042999267578125},{"x":0.01690673828125,"y":-0.290435791015625},{"x":0.08758544921875,"y":-0.203857421875},{"x":0.19769287109375,"y":-0.099212646484375},{"x":-0.08319091796875,"y":0.0338134765625},{"x":-0.130859375,"y":-0.00799560546875},{"x":0.01263427734375,"y":-0.081024169921875},{"x":0.0057373046875,"y":-0.07470703125},{"x":0.1876220703125,"y":0.08477783203125},{"x":0.1868896484375,"y":0.027069091796875},{"x":0.16021728515625,"y":0.341278076171875},{"x":0.20208740234375,"y":0.072174072265625},{"x":-0.04461669921875,"y":0.06573486328125},{"x":0.07977294921875,"y":0.153533935546875},{"x":0.057861328125,"y":0.37908935546875},{"x":0.1141357421875,"y":-0.134552001953125},{"x":0.23876953125,"y":-0.22161865234375},{"x":0.1776123046875,"y":0.010223388671875},{"x":0.267822265625,"y":-0.0479736328125},{"x":0.1199951171875,"y":0.2769775390625},{"x":-0.007080078125,"y":-0.207733154296875},{"x":-0.01629638671875,"y":-0.177825927734375},{"x":0.299560546875,"y":0.09356689453125},{"x":0.0587158203125,"y":0.3594970703125},{"x":0.0716552734375,"y":0.043701171875},{"x":0.2537841796875,"y":0.060455322265625},{"x":-0.04071044921875,"y":-0.166717529296875},{"x":-0.22222900390625,"y":-0.0491943359375},{"x":-0.23736572265625,"y":-0.093994140625}],"optimisedCameraToObject":{"translation":{"x":0.14245953064245973,"y":-0.12445481468657799,"z":0.7443504518235929},"rotation":{"quaternion":{"W":0.9973960137872739,"X":0.020145460484844304,"Y":-0.06754135983809383,"Z":0.015281256961737955}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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}],"locationInImageSpace":[{"x":637.35009765625,"y":223.87112426757812},{"x":658.77880859375,"y":224.62010192871094},{"x":679.959228515625,"y":225.6707763671875},{"x":700.463623046875,"y":226.93467712402344},{"x":721.117919921875,"y":227.92007446289062},{"x":741.12353515625,"y":229.05091857910156},{"x":760.9057006835938,"y":230.06553649902344},{"x":636.3917846679688,"y":246.91290283203125},{"x":657.5963745117188,"y":247.46505737304688},{"x":678.8309326171875,"y":248.7857208251953},{"x":699.7490234375,"y":248.8679656982422},{"x":720.1301879882812,"y":250.70465087890625},{"x":740.2091674804688,"y":251.4678192138672},{"x":759.989501953125,"y":252.2472381591797},{"x":635.3759155273438,"y":270.10894775390625},{"x":656.8347778320312,"y":270.8260192871094},{"x":677.8392333984375,"y":271.9836730957031},{"x":698.5076293945312,"y":272.5318908691406},{"x":718.9074096679688,"y":273.3147888183594},{"x":739.0045776367188,"y":274.07147216796875},{"x":759.0926513671875,"y":274.8702697753906},{"x":633.1982421875,"y":291.47125244140625},{"x":655.77587890625,"y":294.0335388183594},{"x":676.6984252929688,"y":294.57183837890625},{"x":697.7639770507812,"y":295.3775634765625},{"x":718.1151733398438,"y":295.98651123046875},{"x":738.515869140625,"y":296.8659973144531},{"x":757.906494140625,"y":297.4889221191406},{"x":633.0443725585938,"y":316.19464111328125},{"x":654.3695678710938,"y":316.8802795410156},{"x":675.6729125976562,"y":317.1841735839844},{"x":696.2865600585938,"y":317.9710388183594},{"x":716.9566650390625,"y":318.2099304199219},{"x":737.3704833984375,"y":318.9745178222656},{"x":757.2713623046875,"y":319.537109375},{"x":632.0281982421875,"y":339.64007568359375},{"x":653.4033813476562,"y":340.02239990234375},{"x":674.5950927734375,"y":340.1749572753906},{"x":695.5606079101562,"y":340.5608825683594},{"x":715.9942626953125,"y":341.0128173828125},{"x":736.1583251953125,"y":341.24932861328125},{"x":756.4220581054688,"y":341.9186706542969},{"x":631.2296142578125,"y":362.1596984863281},{"x":652.7010498046875,"y":362.4485168457031},{"x":673.944580078125,"y":362.9244079589844},{"x":694.4776611328125,"y":363.163818359375},{"x":715.1163940429688,"y":363.8038635253906}],"reprojectionErrors":[{"x":9.1552734375E-4,"y":-0.4399566650390625},{"x":-0.0999755859375,"y":-0.0617523193359375},{"x":-0.21307373046875,"y":0.0051116943359375},{"x":0.0904541015625,"y":-0.1508941650390625},{"x":-0.01397705078125,"y":-0.038055419921875},{"x":0.27337646484375,"y":-0.0803375244140625},{"x":0.5286865234375,"y":-0.0160369873046875},{"x":-0.00299072265625,"y":-0.24554443359375},{"x":0.1090087890625,"y":0.1974029541015625},{"x":-0.069091796875,"y":-0.137481689453125},{"x":-0.189697265625,"y":0.7567138671875},{"x":-0.0311279296875,"y":-0.11285400390625},{"x":0.17315673828125,"y":0.081787109375},{"x":0.4208984375,"y":0.250885009765625},{"x":0.04638671875,"y":-0.241607666015625},{"x":-0.107421875,"y":-0.095245361328125},{"x":-0.0665283203125,"y":-0.39849853515625},{"x":0.0518798828125,"y":-0.101348876953125},{"x":0.18145751953125,"y":-0.0478515625},{"x":0.3575439453125,"y":0.02288818359375},{"x":0.28790283203125,"y":0.042572021484375},{"x":1.25341796875,"y":1.558807373046875},{"x":-0.03094482421875,"y":-0.27130126953125},{"x":0.0804443359375,"y":-0.086181640625},{"x":-0.2093505859375,"y":-0.17718505859375},{"x":-0.04180908203125,"y":-0.080047607421875},{"x":-0.17950439453125,"y":-0.262115478515625},{"x":0.43841552734375,"y":-0.1961669921875},{"x":0.43255615234375,"y":-0.04010009765625},{"x":0.3885498046875,"y":-0.124420166015625},{"x":0.10748291015625,"y":0.164581298828125},{"x":0.25823974609375,"y":-0.037811279296875},{"x":0.095947265625,"y":0.2994384765625},{"x":-0.06536865234375,"y":0.10272216796875},{"x":0.0321044921875,"y":0.099761962890625},{"x":0.469970703125,"y":-0.400299072265625},{"x":0.36358642578125,"y":-0.311737060546875},{"x":0.18212890625,"y":-0.00152587890625},{"x":-0.030517578125,"y":0.06719970703125},{"x":0.032470703125,"y":0.061920166015625},{"x":0.11004638671875,"y":0.26409912109375},{"x":-0.16571044921875,"y":0.025604248046875},{"x":0.28582763671875,"y":0.12506103515625},{"x":0.07049560546875,"y":0.177154541015625},{"x":-0.175048828125,"y":0.0343017578125},{"x":0.0328369140625,"y":0.12017822265625},{"x":-0.12066650390625,"y":-0.2022705078125}],"optimisedCameraToObject":{"translation":{"x":0.24329282913901001,"y":-0.11484819209175529,"z":0.7410535630740036},"rotation":{"quaternion":{"W":0.9961612850501481,"X":0.013382385078883376,"Y":-0.08508084968790397,"Z":0.015647841807173553}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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.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":638.1043090820312,"y":344.4933776855469},{"x":659.035400390625,"y":345.93658447265625},{"x":679.9313354492188,"y":346.6091003417969},{"x":700.3306274414062,"y":347.8829040527344},{"x":720.4559936523438,"y":348.86962890625},{"x":637.201904296875,"y":367.73736572265625},{"x":658.0675048828125,"y":368.0691223144531},{"x":679.0016479492188,"y":369.27239990234375},{"x":699.8268432617188,"y":370.36151123046875},{"x":720.205078125,"y":371.1315002441406},{"x":636.127197265625,"y":390.8311767578125},{"x":657.3150634765625,"y":391.4880065917969},{"x":678.0411987304688,"y":392.1158142089844},{"x":698.6543579101562,"y":393.0058898925781},{"x":719.1582641601562,"y":393.9601135253906},{"x":739.179931640625,"y":394.6669616699219},{"x":759.0640869140625,"y":395.3464660644531},{"x":635.115478515625,"y":413.9040832519531},{"x":656.3128051757812,"y":414.16644287109375},{"x":677.4334106445312,"y":415.0669250488281},{"x":698.0911254882812,"y":415.8868713378906},{"x":718.63916015625,"y":416.1180114746094},{"x":738.6715087890625,"y":417.0088806152344},{"x":758.2313842773438,"y":417.7875671386719},{"x":634.3212280273438,"y":436.9694519042969},{"x":655.6497802734375,"y":437.10845947265625},{"x":676.3109130859375,"y":437.74090576171875},{"x":697.1973876953125,"y":438.26531982421875},{"x":717.8255004882812,"y":438.8712158203125},{"x":737.9938354492188,"y":439.3226013183594},{"x":757.732421875,"y":440.0768127441406},{"x":633.1463012695312,"y":460.0330505371094},{"x":654.4242553710938,"y":460.2530822753906},{"x":675.4493408203125,"y":461.0587463378906},{"x":696.1884155273438,"y":461.2337646484375},{"x":716.9584350585938,"y":461.78912353515625},{"x":737.077880859375,"y":462.0497741699219},{"x":757.1848754882812,"y":462.3872985839844},{"x":632.2225952148438,"y":483.07745361328125},{"x":653.7341918945312,"y":483.8595886230469},{"x":674.9586791992188,"y":483.8917541503906},{"x":695.8773803710938,"y":484.0645751953125},{"x":716.0153198242188,"y":484.0696716308594},{"x":736.1421508789062,"y":484.6651916503906},{"x":756.3182983398438,"y":484.9635314941406}],"reprojectionErrors":[{"x":-0.06158447265625,"y":0.10858154296875},{"x":0.094482421875,"y":-0.268096923828125},{"x":0.03350830078125,"y":0.112945556640625},{"x":0.21807861328125,"y":-0.120269775390625},{"x":0.42645263671875,"y":-0.079254150390625},{"x":-0.04901123046875,"y":-0.15380859375},{"x":0.20208740234375,"y":0.4552001953125},{"x":0.1319580078125,"y":0.179931640625},{"x":-0.0809326171875,"y":0.006103515625},{"x":-0.0975341796875,"y":0.13873291015625},{"x":0.1280517578125,"y":-0.212982177734375},{"x":0.08624267578125,"y":-0.055389404296875},{"x":0.2529296875,"y":0.11865234375},{"x":0.28033447265625,"y":0.0179443359375},{"x":0.16571044921875,"y":-0.159332275390625},{"x":0.28326416015625,"y":-0.101531982421875},{"x":0.289306640625,"y":-0.028594970703125},{"x":0.23431396484375,"y":-0.1990966796875},{"x":0.2122802734375,"y":0.226043701171875},{"x":0.0130615234375,"y":6.7138671875E-4},{"x":0.02386474609375,"y":-0.15643310546875},{"x":-0.10736083984375,"y":0.26312255859375},{"x":0.02642822265625,"y":0.010894775390625},{"x":0.3831787109375,"y":-0.141082763671875},{"x":0.11541748046875,"y":-0.126434326171875},{"x":-0.00897216796875,"y":0.294525146484375},{"x":0.2796630859375,"y":0.209869384765625},{"x":0.08953857421875,"y":0.221221923828125},{"x":-0.09454345703125,"y":0.13922119140625},{"x":-0.07000732421875,"y":0.199920654296875},{"x":0.13421630859375,"y":-0.05389404296875},{"x":0.369384765625,"y":-0.001708984375},{"x":0.3243408203125,"y":0.210113525390625},{"x":0.27716064453125,"y":-0.175628662109375},{"x":0.26202392578125,"y":0.0574951171875},{"x":-0.036865234375,"y":-0.10137939453125},{"x":0.06304931640625,"y":0.022918701171875},{"x":-0.07513427734375,"y":0.058990478515625},{"x":0.36444091796875,"y":0.191558837890625},{"x":0.11419677734375,"y":-0.287384033203125},{"x":-0.10443115234375,"y":-0.028076171875},{"x":-0.2718505859375,"y":0.07904052734375},{"x":0.08819580078125,"y":0.342498779296875},{"x":0.20703125,"y":0.0042724609375},{"x":0.0255126953125,"y":-0.0478515625}],"optimisedCameraToObject":{"translation":{"x":0.24754713549908436,"y":0.01758448765983381,"z":0.7509637360505108},"rotation":{"quaternion":{"W":0.9959298692199076,"X":-0.014744698700668487,"Y":-0.08468339221670153,"Z":0.027111114667540726}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":447.98565673828125,"y":366.0115051269531},{"x":471.3189392089844,"y":366.892578125},{"x":494.91156005859375,"y":367.2764587402344},{"x":518.9103393554688,"y":367.99835205078125},{"x":542.2122192382812,"y":368.39337158203125},{"x":565.9973754882812,"y":369.1334228515625},{"x":589.6964721679688,"y":370.1134338378906},{"x":447.24810791015625,"y":389.4342041015625},{"x":470.78436279296875,"y":390.0230407714844},{"x":494.425048828125,"y":390.985107421875},{"x":518.0431518554688,"y":391.7659912109375},{"x":541.5393676757812,"y":392.0966796875},{"x":565.402099609375,"y":392.8497009277344},{"x":589.0236206054688,"y":393.3424072265625},{"x":446.2716979980469,"y":412.9163818359375},{"x":470.0987243652344,"y":413.42156982421875},{"x":493.56207275390625,"y":414.0374450683594},{"x":517.07666015625,"y":415.053955078125},{"x":540.9677124023438,"y":415.93798828125},{"x":564.7122192382812,"y":416.229736328125},{"x":588.1357421875,"y":416.99365234375},{"x":445.8376770019531,"y":436.2386779785156},{"x":469.4493103027344,"y":437.2322082519531},{"x":492.94622802734375,"y":437.9151306152344},{"x":516.6016845703125,"y":438.303466796875},{"x":540.1926879882812,"y":439.3043518066406},{"x":563.9985961914062,"y":440.0093078613281},{"x":587.4954223632812,"y":440.4448547363281},{"x":445.2002258300781,"y":459.3562927246094},{"x":468.8190612792969,"y":459.9555358886719},{"x":492.0570983886719,"y":461.02642822265625},{"x":515.9443359375,"y":461.81158447265625},{"x":539.57275390625,"y":462.4569091796875},{"x":562.9671020507812,"y":463.0577392578125},{"x":586.8317260742188,"y":463.97418212890625},{"x":444.7334289550781,"y":482.88525390625},{"x":468.0389099121094,"y":483.9429016113281},{"x":491.6917724609375,"y":484.2176818847656},{"x":515.029541015625,"y":485.1873474121094},{"x":538.8141479492188,"y":485.9776916503906},{"x":562.1469116210938,"y":486.8894958496094},{"x":586.2509155273438,"y":487.6807556152344},{"x":443.9853515625,"y":506.1192932128906},{"x":467.69268798828125,"y":507.0080261230469},{"x":491.01971435546875,"y":507.8973083496094},{"x":514.5439453125,"y":508.4829406738281},{"x":538.0091552734375,"y":509.1659851074219},{"x":561.7861938476562,"y":510.05413818359375},{"x":585.3952026367188,"y":510.97589111328125}],"reprojectionErrors":[{"x":-0.16455078125,"y":-0.012786865234375},{"x":0.06915283203125,"y":-0.227935791015625},{"x":0.087310791015625,"y":0.05126953125},{"x":-0.2606201171875,"y":-0.010498046875},{"x":0.124755859375,"y":0.251556396484375},{"x":0.05950927734375,"y":0.16534423828125},{"x":0.109130859375,"y":-0.16412353515625},{"x":-0.054412841796875,"y":0.0311279296875},{"x":-0.04248046875,"y":0.1317138671875},{"x":-0.09124755859375,"y":-0.144989013671875},{"x":-0.077392578125,"y":-0.244720458984375},{"x":0.09478759765625,"y":0.101470947265625},{"x":-0.06695556640625,"y":0.0208740234375},{"x":0.04132080078125,"y":0.196044921875},{"x":0.29498291015625,"y":-0.022552490234375},{"x":-0.0030517578125,"y":0.18505859375},{"x":0.106353759765625,"y":0.2767333984375},{"x":0.20452880859375,"y":-0.03765869140625},{"x":-0.03741455078125,"y":-0.22509765625},{"x":-0.10028076171875,"y":0.174072265625},{"x":0.186767578125,"y":0.095306396484375},{"x":0.1024169921875,"y":0.04443359375},{"x":2.74658203125E-4,"y":-0.212982177734375},{"x":0.0565185546875,"y":-0.166290283203125},{"x":-0.00579833984375,"y":0.16839599609375},{"x":0.03271484375,"y":-0.116241455078125},{"x":-0.11114501953125,"y":-0.111846923828125},{"x":0.0828857421875,"y":0.15496826171875},{"x":0.113739013671875,"y":0.275848388671875},{"x":-0.0155029296875,"y":0.4359130859375},{"x":0.27972412109375,"y":0.116668701171875},{"x":-0.0343017578125,"y":0.0753173828125},{"x":-0.05322265625,"y":0.16583251953125},{"x":0.1944580078125,"y":0.292724609375},{"x":7.32421875E-4,"y":0.095733642578125},{"x":-0.045135498046875,"y":0.054595947265625},{"x":0.1187744140625,"y":-0.220611572265625},{"x":-0.021087646484375,"y":0.27813720703125},{"x":0.19403076171875,"y":0.072998046875},{"x":-0.00140380859375,"y":0.037994384765625},{"x":0.28753662109375,"y":-0.1278076171875},{"x":-0.16595458984375,"y":-0.182525634765625},{"x":0.07781982421875,"y":0.085906982421875},{"x":-0.18072509765625,"y":0.00262451171875},{"x":-0.015380859375,"y":-0.091278076171875},{"x":-0.00732421875,"y":0.108245849609375},{"x":0.095947265625,"y":0.199951171875},{"x":-0.08013916015625,"y":0.076019287109375},{"x":-0.05938720703125,"y":-0.09222412109375}],"optimisedCameraToObject":{"translation":{"x":0.034122441749156095,"y":0.04029431283328029,"z":0.7354364688351985},"rotation":{"quaternion":{"W":0.99976524130964,"X":0.011462634446365406,"Y":0.013384081574993042,"Z":0.012607007615623483}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img4.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.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":341.9446716308594,"y":338.99041748046875},{"x":365.12640380859375,"y":339.4508361816406},{"x":388.7294616699219,"y":339.88134765625},{"x":412.1387023925781,"y":340.0793151855469},{"x":435.2712707519531,"y":340.35601806640625},{"x":294.0413513183594,"y":361.9755859375},{"x":317.7515869140625,"y":362.07501220703125},{"x":341.30120849609375,"y":362.3594055175781},{"x":365.0148010253906,"y":362.88714599609375},{"x":388.31292724609375,"y":363.0168762207031},{"x":412.0378723144531,"y":363.3788757324219},{"x":435.04156494140625,"y":363.8414611816406},{"x":293.6105041503906,"y":385.682373046875},{"x":317.1171569824219,"y":385.960693359375},{"x":340.89471435546875,"y":385.9474792480469},{"x":364.3169860839844,"y":386.28466796875},{"x":387.9880065917969,"y":386.3755187988281},{"x":411.0895690917969,"y":386.97198486328125},{"x":434.33612060546875,"y":386.9864501953125},{"x":293.20263671875,"y":409.2626647949219},{"x":316.90667724609375,"y":409.6739501953125},{"x":340.19635009765625,"y":409.7577209472656},{"x":364.0110778808594,"y":410.09033203125},{"x":387.60369873046875,"y":410.1377258300781},{"x":410.83807373046875,"y":410.35369873046875},{"x":434.2080993652344,"y":410.4848327636719},{"x":292.97564697265625,"y":432.27581787109375},{"x":316.2349853515625,"y":432.9315490722656},{"x":340.0411682128906,"y":433.0538024902344},{"x":363.7281188964844,"y":433.0025939941406},{"x":387.02880859375,"y":433.3888854980469},{"x":410.2279968261719,"y":433.9454040527344},{"x":433.7293395996094,"y":433.92034912109375},{"x":292.1387023925781,"y":456.2340393066406},{"x":315.9443664550781,"y":456.1676940917969},{"x":339.37628173828125,"y":456.473388671875},{"x":363.09979248046875,"y":456.6989440917969},{"x":386.5052490234375,"y":457.0135192871094},{"x":409.8800964355469,"y":457.0748596191406},{"x":433.2568359375,"y":457.6296691894531},{"x":291.862548828125,"y":480.00738525390625},{"x":315.5344543457031,"y":479.99676513671875},{"x":338.9934387207031,"y":480.0941467285156},{"x":362.78179931640625,"y":480.2334899902344},{"x":386.0271301269531,"y":480.3453063964844},{"x":409.4964599609375,"y":480.4708251953125},{"x":432.8271789550781,"y":480.8829345703125}],"reprojectionErrors":[{"x":-0.20916748046875,"y":-0.027313232421875},{"x":0.15557861328125,"y":-0.11175537109375},{"x":0.018829345703125,"y":-0.16961669921875},{"x":-0.007598876953125,"y":0.001678466796875},{"x":0.155792236328125,"y":0.090789794921875},{"x":-0.052703857421875,"y":-0.13916015625},{"x":-0.0687255859375,"y":0.106781005859375},{"x":0.002593994140625,"y":0.163360595703125},{"x":-0.166778564453125,"y":-0.02783203125},{"x":-8.23974609375E-4,"y":0.174468994140625},{"x":-0.345184326171875,"y":0.140045166015625},{"x":-0.0550537109375,"y":4.8828125E-4},{"x":-0.047637939453125,"y":-0.21826171875},{"x":0.137176513671875,"y":-0.1883544921875},{"x":-0.02215576171875,"y":0.127532958984375},{"x":0.09710693359375,"y":0.087432861328125},{"x":-0.112457275390625,"y":0.2880859375},{"x":0.16400146484375,"y":-0.022491455078125},{"x":0.208709716796875,"y":0.2432861328125},{"x":-0.0643310546875,"y":-0.179473876953125},{"x":-0.080047607421875,"y":-0.31964111328125},{"x":0.245391845703125,"y":-0.1390380859375},{"x":-0.030853271484375,"y":-0.213958740234375},{"x":-0.165008544921875,"y":-0.010406494140625},{"x":-0.024322509765625,"y":0.017852783203125},{"x":-0.105987548828125,"y":0.12420654296875},{"x":-0.260650634765625,"y":0.41668701171875},{"x":0.164794921875,"y":-0.00506591796875},{"x":-0.029754638671875,"y":0.09881591796875},{"x":-0.181640625,"y":0.368316650390625},{"x":-0.02728271484375,"y":0.192474365234375},{"x":0.145233154296875,"y":-0.161468505859375},{"x":-0.071014404296875,"y":0.058349609375},{"x":0.154266357421875,"y":0.05682373046875},{"x":0.029449462890625,"y":0.320068359375},{"x":0.205291748046875,"y":0.2022705078125},{"x":0.013031005859375,"y":0.1556396484375},{"x":0.058837890625,"y":0.011016845703125},{"x":0.052001953125,"y":0.110687255859375},{"x":-0.0433349609375,"y":-0.29205322265625},{"x":0.009674072265625,"y":-0.130279541015625},{"x":0.014312744140625,"y":0.040191650390625},{"x":0.158843994140625,"y":0.092529296875},{"x":-0.102508544921875,"y":0.0927734375},{"x":0.099273681640625,"y":0.110443115234375},{"x":-0.00616455078125,"y":0.1043701171875},{"x":-0.05950927734375,"y":-0.198333740234375}],"optimisedCameraToObject":{"translation":{"x":-0.13134416977800117,"y":0.010323779633028083,"z":0.7308503926451307},"rotation":{"quaternion":{"W":0.9996605905981145,"X":0.0025480876132541507,"Y":-0.024209947028352042,"Z":0.009278433026567359}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":97.61500549316406,"y":336.0641784667969},{"x":120.96920013427734,"y":336.9745788574219},{"x":144.57666015625,"y":337.9964294433594},{"x":168.98252868652344,"y":339.07489013671875},{"x":193.4680633544922,"y":340.1340026855469},{"x":218.22116088867188,"y":341.0326843261719},{"x":243.0047149658203,"y":342.2440185546875},{"x":96.71175384521484,"y":361.75238037109375},{"x":120.14875030517578,"y":363.01373291015625},{"x":144.02333068847656,"y":364.2213134765625},{"x":167.95489501953125,"y":365.3166809082031},{"x":192.05722045898438,"y":366.85107421875},{"x":217.23483276367188,"y":367.7889404296875},{"x":242.24429321289062,"y":369.021484375},{"x":95.8846206665039,"y":387.8974914550781},{"x":119.16228485107422,"y":389.06158447265625},{"x":142.9612579345703,"y":390.18646240234375},{"x":167.1494598388672,"y":391.8658752441406},{"x":191.63900756835938,"y":393.1479187011719},{"x":216.1166229248047,"y":394.6579895019531},{"x":241.18560791015625,"y":395.9226989746094},{"x":94.93936920166016,"y":413.6061096191406},{"x":115.83428192138672,"y":414.9969787597656},{"x":141.81893920898438,"y":416.3804016113281},{"x":165.98773193359375,"y":418.0617980957031},{"x":190.3942108154297,"y":419.70068359375},{"x":214.9544677734375,"y":421.1881103515625},{"x":240.09629821777344,"y":422.9295349121094},{"x":93.96711730957031,"y":439.213623046875},{"x":117.5584716796875,"y":440.8392333984375},{"x":141.13279724121094,"y":442.50592041015625},{"x":165.27101135253906,"y":444.16400146484375},{"x":189.60659790039062,"y":446.014404296875},{"x":214.26260375976562,"y":447.7445373535156},{"x":239.14639282226562,"y":449.69683837890625},{"x":93.1928482055664,"y":465.23236083984375},{"x":116.59505462646484,"y":467.13543701171875},{"x":140.275390625,"y":468.8777770996094},{"x":164.19371032714844,"y":470.8779602050781},{"x":188.3455352783203,"y":472.8445739746094},{"x":213.3333740234375,"y":474.8539123535156},{"x":238.15150451660156,"y":476.9864807128906},{"x":92.7521743774414,"y":490.61322021484375},{"x":115.98404693603516,"y":493.0165710449219},{"x":139.02304077148438,"y":494.95001220703125},{"x":163.232177734375,"y":497.1293640136719},{"x":187.41690063476562,"y":499.2298889160156},{"x":212.11880493164062,"y":501.5762634277344},{"x":237.01295471191406,"y":503.8286437988281}],"reprojectionErrors":[{"x":-0.02103424072265625,"y":0.018890380859375},{"x":-0.04674530029296875,"y":0.102447509765625},{"x":0.0291900634765625,"y":0.08740234375},{"x":-0.334991455078125,"y":0.028717041015625},{"x":-0.41717529296875,"y":0.00238037109375},{"x":-0.401947021484375,"y":0.14959716796875},{"x":-0.0489044189453125,"y":-0.002593994140625},{"x":-0.066864013671875,"y":0.088714599609375},{"x":-0.17259979248046875,"y":0.004302978515625},{"x":-0.3607635498046875,"y":-0.012420654296875},{"x":-0.24737548828125,"y":0.097076416015625},{"x":0.057159423828125,"y":-0.218353271484375},{"x":-0.348358154296875,"y":0.076934814453125},{"x":-0.2171783447265625,"y":0.091796875},{"x":-0.18206787109375,"y":-0.27880859375},{"x":-0.126068115234375,"y":-0.082733154296875},{"x":-0.235992431640625,"y":0.16754150390625},{"x":-0.376373291015625,"y":-0.121612548828125},{"x":-0.4559326171875,"y":0.001800537109375},{"x":-0.1580963134765625,"y":-0.087615966796875},{"x":-0.08282470703125,"y":0.083648681640625},{"x":-0.17237091064453125,"y":-0.191619873046875},{"x":2.2684326171875,"y":-0.038848876953125},{"x":-0.0249176025390625,"y":0.137451171875},{"x":-0.143402099609375,"y":0.031951904296875},{"x":-0.1371917724609375,"y":-0.0147705078125},{"x":0.080963134765625,"y":0.106231689453125},{"x":0.0865631103515625,"y":-0.010406494140625},{"x":-0.12882232666015625,"y":0.0135498046875},{"x":-0.382781982421875,"y":0.115264892578125},{"x":-0.263916015625,"y":0.193084716796875},{"x":-0.3497314453125,"y":0.296783447265625},{"x":-0.27032470703125,"y":0.225494384765625},{"x":-0.1453857421875,"y":0.29180908203125},{"x":0.1210174560546875,"y":0.153350830078125},{"x":-0.27634429931640625,"y":-0.177001953125},{"x":-0.33985137939453125,"y":-0.168853759765625},{"x":-0.3254852294921875,"y":0.018341064453125},{"x":-0.1897125244140625,"y":-0.03399658203125},{"x":0.07537841796875,"y":-0.03436279296875},{"x":-0.1294097900390625,"y":-0.05902099609375},{"x":0.2049713134765625,"y":-0.188446044921875},{"x":-0.7505111694335938,"y":0.28448486328125},{"x":-0.642730712890625,"y":-0.0235595703125},{"x":0.01409912109375,"y":0.15771484375},{"x":-0.139617919921875,"y":0.11248779296875},{"x":0.0940704345703125,"y":0.16558837890625},{"x":0.176910400390625,"y":-0.0076904296875},{"x":0.4371795654296875,"y":-0.067474365234375}],"optimisedCameraToObject":{"translation":{"x":-0.31634823929517963,"y":0.005004095891901554,"z":0.6773106464321457},"rotation":{"quaternion":{"W":0.9956302433989785,"X":-0.006336032326604208,"Y":0.09186517925814541,"Z":0.0155261702784586}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img6.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.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":179.23895263671875,"y":156.03054809570312},{"x":206.84190368652344,"y":157.575927734375},{"x":233.7938232421875,"y":159.07339477539062},{"x":260.92828369140625,"y":160.43203735351562},{"x":287.8433837890625,"y":162.00180053710938},{"x":124.97286987304688,"y":180.41293334960938},{"x":152.35006713867188,"y":181.77638244628906},{"x":179.15428161621094,"y":183.2238311767578},{"x":206.3820037841797,"y":185.00515747070312},{"x":233.23191833496094,"y":186.0235137939453},{"x":260.3642578125,"y":187.92788696289062},{"x":287.0011291503906,"y":189.0528106689453},{"x":125.74578857421875,"y":207.88568115234375},{"x":152.55030822753906,"y":209.0631561279297},{"x":179.2863311767578,"y":210.15814208984375},{"x":206.33233642578125,"y":211.95249938964844},{"x":233.13067626953125,"y":213.15518188476562},{"x":259.935546875,"y":214.81695556640625},{"x":286.2164001464844,"y":215.9636688232422},{"x":125.94800567626953,"y":234.4815673828125},{"x":152.9366912841797,"y":235.94944763183594},{"x":179.3036346435547,"y":237.1339874267578},{"x":206.16748046875,"y":238.9255828857422},{"x":232.71083068847656,"y":239.97129821777344},{"x":259.2073669433594,"y":241.254638671875},{"x":285.5835876464844,"y":242.48013305664062},{"x":126.11270141601562,"y":260.6037292480469},{"x":152.958984375,"y":261.9674987792969},{"x":179.239990234375,"y":263.461181640625},{"x":206.18199157714844,"y":264.637939453125},{"x":232.71420288085938,"y":265.9879455566406},{"x":259.0379638671875,"y":267.2241516113281},{"x":284.8939514160156,"y":268.3166809082031},{"x":126.67525482177734,"y":286.9856262207031},{"x":153.09518432617188,"y":288.2422790527344},{"x":179.4561309814453,"y":289.4141540527344},{"x":206.04443359375,"y":290.98602294921875},{"x":231.97097778320312,"y":292.051513671875},{"x":258.12689208984375,"y":293.20037841796875},{"x":284.2055358886719,"y":294.75848388671875},{"x":126.91804504394531,"y":312.7438049316406},{"x":153.3087158203125,"y":314.0313720703125},{"x":179.20553588867188,"y":315.157470703125},{"x":205.6704559326172,"y":316.26654052734375},{"x":231.98622131347656,"y":317.78912353515625},{"x":257.77471923828125,"y":318.8023681640625},{"x":283.75274658203125,"y":319.9034423828125}],"reprojectionErrors":[{"x":0.0879974365234375,"y":-0.060394287109375},{"x":-0.28436279296875,"y":-0.1079864501953125},{"x":-0.0784454345703125,"y":-0.11053466796875},{"x":-0.132415771484375,"y":0.0225982666015625},{"x":-0.048919677734375,"y":-0.0587615966796875},{"x":0.07080841064453125,"y":0.082489013671875},{"x":-0.128143310546875,"y":0.174102783203125},{"x":0.18341064453125,"y":0.1778564453125},{"x":0.0043487548828125,"y":-0.1563873291015625},{"x":0.1313934326171875,"y":0.26800537109375},{"x":-0.1002197265625,"y":-0.1982269287109375},{"x":0.0828857421875,"y":0.11016845703125},{"x":-0.3250885009765625,"y":-0.229156494140625},{"x":-0.1332550048828125,"y":0.0018463134765625},{"x":0.065521240234375,"y":0.30999755859375},{"x":-0.111846923828125,"y":-0.0867767333984375},{"x":-0.1121978759765625,"y":0.102325439453125},{"x":-0.194244384765625,"y":-0.1736907958984375},{"x":0.168121337890625,"y":0.05914306640625},{"x":-0.1507720947265625,"y":-0.0254364013671875},{"x":-0.32305908203125,"y":-0.1303558349609375},{"x":0.0657196044921875,"y":0.0413055419921875},{"x":-0.10760498046875,"y":-0.4010772705078125},{"x":-0.03009033203125,"y":-0.104766845703125},{"x":0.0201416015625,"y":-0.0534820556640625},{"x":0.11224365234375,"y":0.04803466796875},{"x":0.060577392578125,"y":0.29620361328125},{"x":-0.1473846435546875,"y":0.250946044921875},{"x":0.150146484375,"y":0.067626953125},{"x":-0.277587890625,"y":0.192840576171875},{"x":-0.36419677734375,"y":0.136260986328125},{"x":-0.3154296875,"y":0.184722900390625},{"x":0.123779296875,"y":0.367950439453125},{"x":-0.12644195556640625,"y":0.0079345703125},{"x":-0.0842437744140625,"y":0.0263671875},{"x":-0.0420074462890625,"y":0.12005615234375},{"x":-0.29046630859375,"y":-0.195953369140625},{"x":0.055145263671875,"y":-0.015472412109375},{"x":0.099365234375,"y":0.071533203125},{"x":0.144561767578125,"y":-0.260894775390625},{"x":0.00579071044921875,"y":-0.0013427734375},{"x":-0.0971221923828125,"y":-0.056243896484375},{"x":0.2357330322265625,"y":0.03948974609375},{"x":-0.06195068359375,"y":0.141204833984375},{"x":-0.2772216796875,"y":-0.1817626953125},{"x":-0.0362548828125,"y":-0.006744384765625},{"x":-0.060028076171875,"y":0.068939208984375}],"optimisedCameraToObject":{"translation":{"x":-0.2760527131762726,"y":-0.16813565080691012,"z":0.6330842627409643},"rotation":{"quaternion":{"W":0.9958270942445676,"X":0.0861069674245715,"Y":-0.01674666803319107,"Z":0.02517017360192109}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":57.41508102416992,"y":156.19703674316406},{"x":88.99311828613281,"y":157.35690307617188},{"x":119.76762390136719,"y":158.71072387695312},{"x":149.94705200195312,"y":160.00352478027344},{"x":179.50148010253906,"y":161.0408172607422},{"x":208.46078491210938,"y":162.5142059326172},{"x":236.79595947265625,"y":163.6628875732422},{"x":58.5984001159668,"y":185.36453247070312},{"x":89.9607925415039,"y":186.656982421875},{"x":120.48433685302734,"y":187.71035766601562},{"x":150.64244079589844,"y":188.2244873046875},{"x":179.9647216796875,"y":189.1368408203125},{"x":208.9032745361328,"y":190.31033325195312},{"x":236.91464233398438,"y":191.21859741210938},{"x":59.5854606628418,"y":214.94866943359375},{"x":90.7377700805664,"y":215.4237823486328},{"x":121.02872467041016,"y":216.00228881835938},{"x":151.19020080566406,"y":216.80926513671875},{"x":180.44345092773438,"y":217.26138305664062},{"x":209.03707885742188,"y":217.996337890625},{"x":237.1096954345703,"y":218.5461883544922},{"x":60.847633361816406,"y":243.88116455078125},{"x":91.74215698242188,"y":243.96539306640625},{"x":122.04385375976562,"y":244.24766540527344},{"x":151.85208129882812,"y":244.97593688964844},{"x":180.99331665039062,"y":245.09634399414062},{"x":209.54660034179688,"y":245.72637939453125},{"x":237.21009826660156,"y":245.82479858398438},{"x":61.71562194824219,"y":272.03814697265625},{"x":92.52717590332031,"y":272.0182189941406},{"x":122.6902084350586,"y":272.0984802246094},{"x":152.42367553710938,"y":272.17254638671875},{"x":181.26165771484375,"y":272.3561706542969},{"x":209.96560668945312,"y":272.5198669433594},{"x":237.74310302734375,"y":272.65740966796875},{"x":62.60470199584961,"y":300.67266845703125},{"x":93.18622589111328,"y":300.3593444824219},{"x":123.37718200683594,"y":300.1873779296875},{"x":152.89686584472656,"y":299.9823913574219},{"x":181.74166870117188,"y":299.9992370605469},{"x":210.09332275390625,"y":299.8036804199219},{"x":237.92066955566406,"y":299.5470886230469},{"x":63.69561767578125,"y":328.34100341796875},{"x":94.06459045410156,"y":327.9868469238281},{"x":123.91429901123047,"y":327.7765197753906},{"x":153.45877075195312,"y":327.0889587402344},{"x":182.05250549316406,"y":326.84765625},{"x":210.35548400878906,"y":326.0143127441406},{"x":238.03480529785156,"y":325.7134094238281}],"reprojectionErrors":[{"x":0.1119842529296875,"y":-0.3919219970703125},{"x":0.02770233154296875,"y":-0.214111328125},{"x":0.07772064208984375,"y":-0.2551116943359375},{"x":0.069244384765625,"y":-0.259429931640625},{"x":0.0474853515625,"y":-0.0319976806640625},{"x":-0.002593994140625,"y":-0.2639312744140625},{"x":-0.037567138671875,"y":-0.19390869140625},{"x":-0.008991241455078125,"y":0.012451171875},{"x":-0.04515838623046875,"y":-0.2676544189453125},{"x":0.09510040283203125,"y":-0.328277587890625},{"x":-0.0462188720703125,"y":0.13116455078125},{"x":0.0162811279296875,"y":0.1736297607421875},{"x":-0.1548919677734375,"y":-0.0633544921875},{"x":-0.0020599365234375,"y":-0.0530242919921875},{"x":0.058612823486328125,"y":-0.2945556640625},{"x":0.06613922119140625,"y":-0.0762939453125},{"x":0.27931976318359375,"y":0.0240631103515625},{"x":-0.0185699462890625,"y":-0.1182403564453125},{"x":-0.03399658203125,"y":0.0804595947265625},{"x":-0.001220703125,"y":-0.0172271728515625},{"x":-0.04486083984375,"y":0.0569610595703125},{"x":-0.15651702880859375,"y":-0.2419586181640625},{"x":-0.05646514892578125,"y":0.0544586181640625},{"x":-0.01263427734375,"y":0.1432647705078125},{"x":-0.1094818115234375,"y":-0.2233123779296875},{"x":-0.1589508056640625,"y":0.0088653564453125},{"x":-0.2259674072265625,"y":-0.2775115966796875},{"x":0.00506591796875,"y":-0.04095458984375},{"x":0.01496124267578125,"y":0.29681396484375},{"x":0.033843994140625,"y":0.390838623046875},{"x":0.05877685546875,"y":0.37982177734375},{"x":-0.1145477294921875,"y":0.370330810546875},{"x":-0.0059051513671875,"y":0.246734619140625},{"x":-0.3628692626953125,"y":0.13861083984375},{"x":-0.379486083984375,"y":0.0523681640625},{"x":0.15783309936523438,"y":0.071380615234375},{"x":0.24372100830078125,"y":0.15826416015625},{"x":0.0842132568359375,"y":0.10357666015625},{"x":-0.0255889892578125,"y":0.08172607421875},{"x":-0.068023681640625,"y":-0.16204833984375},{"x":-0.2111358642578125,"y":-0.193511962890625},{"x":-0.4104766845703125,"y":-0.16400146484375},{"x":0.09140396118164062,"y":0.528106689453125},{"x":0.22792816162109375,"y":0.36126708984375},{"x":0.25417327880859375,"y":0.0548095703125},{"x":-0.0297088623046875,"y":0.22979736328125},{"x":0.03558349609375,"y":-0.037322998046875},{"x":-0.1964874267578125,"y":0.291748046875},{"x":-0.3798828125,"y":0.09246826171875}],"optimisedCameraToObject":{"translation":{"x":-0.31682738866197047,"y":-0.15442123887700634,"z":0.5837741642520742},"rotation":{"quaternion":{"W":0.9896064788088634,"X":0.060269292242198874,"Y":-0.13052865213700213,"Z":0.0029833678023946995}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":121.498291015625,"y":53.990806579589844},{"x":152.80255126953125,"y":56.918514251708984},{"x":182.77249145507812,"y":60.02717590332031},{"x":212.13917541503906,"y":63.19260025024414},{"x":241.0860595703125,"y":66.34115600585938},{"x":269.3520202636719,"y":69.32079315185547},{"x":296.61553955078125,"y":72.13152313232422},{"x":122.40913391113281,"y":84.04911041259766},{"x":152.94232177734375,"y":87.03606414794922},{"x":182.64622497558594,"y":89.82044982910156},{"x":211.99856567382812,"y":92.87154388427734},{"x":240.2277069091797,"y":95.26178741455078},{"x":268.3757019042969,"y":98.13613891601562},{"x":295.08251953125,"y":100.46299743652344},{"x":122.9631576538086,"y":114.066650390625},{"x":153.1135711669922,"y":116.20465087890625},{"x":182.8377685546875,"y":118.85829162597656},{"x":211.72305297851562,"y":121.32259368896484},{"x":239.81072998046875,"y":123.81327056884766},{"x":267.23480224609375,"y":126.0376205444336},{"x":294.04949951171875,"y":128.16526794433594},{"x":123.73482513427734,"y":143.07183837890625},{"x":153.5081024169922,"y":145.32656860351562},{"x":182.72732543945312,"y":147.56631469726562},{"x":211.32582092285156,"y":149.5387725830078},{"x":239.15919494628906,"y":151.69857788085938},{"x":266.5666809082031,"y":153.849853515625},{"x":292.94976806640625,"y":155.68409729003906},{"x":124.13727569580078,"y":171.1220245361328},{"x":153.74205017089844,"y":173.11196899414062},{"x":182.71836853027344,"y":174.9853057861328},{"x":211.1621856689453,"y":176.79493713378906},{"x":238.49862670898438,"y":178.4734649658203},{"x":265.8219299316406,"y":179.92453002929688},{"x":291.9144592285156,"y":181.8324432373047},{"x":124.96066284179688,"y":199.2381591796875},{"x":154.14083862304688,"y":200.70486450195312},{"x":182.53627014160156,"y":202.15652465820312},{"x":211.05850219726562,"y":203.87747192382812},{"x":238.02357482910156,"y":205.3922119140625},{"x":264.8962707519531,"y":206.5952911376953},{"x":290.74957275390625,"y":207.96823120117188},{"x":125.76335144042969,"y":226.06118774414062},{"x":154.38156127929688,"y":227.59100341796875},{"x":182.76058959960938,"y":228.87582397460938},{"x":210.5233612060547,"y":229.92601013183594},{"x":237.17413330078125,"y":230.9891815185547},{"x":263.8055419921875,"y":231.99871826171875},{"x":289.68231201171875,"y":233.29197692871094}],"reprojectionErrors":[{"x":0.40013885498046875,"y":-0.13199615478515625},{"x":-0.1141510009765625,"y":0.092437744140625},{"x":0.053436279296875,"y":0.07014083862304688},{"x":0.1871337890625,"y":-0.073150634765625},{"x":0.1184234619140625,"y":-0.2623138427734375},{"x":0.122894287109375,"y":-0.34384918212890625},{"x":0.5361328125,"y":-0.31635284423828125},{"x":0.173309326171875,"y":0.34326171875},{"x":0.0511627197265625,"y":0.14636993408203125},{"x":0.1215972900390625,"y":0.09288787841796875},{"x":-0.078369140625,"y":-0.2850799560546875},{"x":0.2371826171875,"y":-0.0586395263671875},{"x":0.040130615234375,"y":-0.3714599609375},{"x":0.704071044921875,"y":-0.19066619873046875},{"x":0.28850555419921875,"y":0.12259674072265625},{"x":0.1788482666015625,"y":0.42889404296875},{"x":-0.126068115234375,"y":0.16655731201171875},{"x":-0.1994171142578125,"y":0.04180145263671875},{"x":-0.068756103515625,"y":-0.1598968505859375},{"x":0.145294189453125,"y":-0.14469146728515625},{"x":0.40155029296875,"y":-0.0810546875},{"x":0.17177581787109375,"y":0.2023162841796875},{"x":0.07733154296875,"y":0.0616302490234375},{"x":-0.06982421875,"y":-0.111328125},{"x":-0.189483642578125,"y":-0.063140869140625},{"x":-0.1239776611328125,"y":-0.247406005859375},{"x":-0.19970703125,"y":-0.467193603515625},{"x":0.19439697265625,"y":-0.4130096435546875},{"x":0.41043853759765625,"y":0.5487518310546875},{"x":0.130645751953125,"y":0.357330322265625},{"x":-0.113250732421875,"y":0.2406005859375},{"x":-0.4041748046875,"y":0.14666748046875},{"x":-0.154541015625,"y":0.1438446044921875},{"x":-0.446197509765625,"y":0.3294219970703125},{"x":-0.049407958984375,"y":0.0199737548828125},{"x":0.21479034423828125,"y":0.163543701171875},{"x":0.013580322265625,"y":0.19384765625},{"x":0.0182647705078125,"y":0.2022705078125},{"x":-0.6701507568359375,"y":-0.0946502685546875},{"x":-0.35546875,"y":-0.2205810546875},{"x":-0.490570068359375,"y":-0.069244384765625},{"x":-0.136749267578125,"y":-0.1213836669921875},{"x":0.02690887451171875,"y":0.427398681640625},{"x":0.0491943359375,"y":0.1063995361328125},{"x":-0.254913330078125,"y":-0.0018768310546875},{"x":-0.496246337890625,"y":0.09295654296875},{"x":-0.167327880859375,"y":0.14404296875},{"x":-0.349273681640625,"y":0.218719482421875},{"x":-0.295654296875,"y":-0.019683837890625}],"optimisedCameraToObject":{"translation":{"x":-0.2589255119836698,"y":-0.2427933664565841,"z":0.5794595409873905},"rotation":{"quaternion":{"W":0.9799898600304914,"X":0.15112811622543043,"Y":-0.12665594043243533,"Z":0.027174242891865284}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img9.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.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":368.96942138671875,"y":65.91423034667969},{"x":394.7527160644531,"y":68.37458801269531},{"x":420.1780090332031,"y":71.0488510131836},{"x":445.78509521484375,"y":73.36840057373047},{"x":470.6046447753906,"y":75.95154571533203},{"x":314.7372131347656,"y":88.21711730957031},{"x":341.0360412597656,"y":90.98574829101562},{"x":366.9888000488281,"y":93.33760070800781},{"x":392.5150146484375,"y":95.95301055908203},{"x":418.0399475097656,"y":98.00727081298828},{"x":443.07025146484375,"y":100.13579559326172},{"x":467.89703369140625,"y":102.49778747558594},{"x":313.11602783203125,"y":115.67381286621094},{"x":339.1872863769531,"y":117.75653839111328},{"x":364.7945861816406,"y":120.06047058105469},{"x":390.2063293457031,"y":122.28267669677734},{"x":415.67510986328125,"y":124.62423706054688},{"x":440.2027282714844,"y":126.98479461669922},{"x":464.5322570800781,"y":128.86172485351562},{"x":312.06475830078125,"y":142.3632049560547},{"x":337.8204650878906,"y":144.66485595703125},{"x":363.01287841796875,"y":146.4701690673828},{"x":388.13897705078125,"y":148.6481475830078},{"x":412.9828796386719,"y":150.8267059326172},{"x":437.5090637207031,"y":152.89230346679688},{"x":461.7171325683594,"y":154.56932067871094},{"x":310.88775634765625,"y":167.99945068359375},{"x":336.168212890625,"y":170.04751586914062},{"x":361.23297119140625,"y":171.98519897460938},{"x":386.1593933105469,"y":173.76931762695312},{"x":410.58807373046875,"y":175.82652282714844},{"x":434.97796630859375,"y":177.66421508789062},{"x":459.1220703125,"y":179.35121154785156},{"x":309.3921813964844,"y":193.74652099609375},{"x":334.4606018066406,"y":195.2259063720703},{"x":359.1919250488281,"y":197.087646484375},{"x":384.038818359375,"y":199.06268310546875},{"x":408.24017333984375,"y":200.8028564453125},{"x":432.36810302734375,"y":202.51919555664062},{"x":456.02386474609375,"y":204.09336853027344},{"x":308.0807189941406,"y":218.32484436035156},{"x":333.08843994140625,"y":219.972412109375},{"x":357.6921691894531,"y":221.58998107910156},{"x":381.98858642578125,"y":223.1558380126953},{"x":406.2618408203125,"y":224.88003540039062},{"x":429.88946533203125,"y":226.60678100585938},{"x":453.58502197265625,"y":228.1021270751953}],"reprojectionErrors":[{"x":-0.04827880859375,"y":0.08437347412109375},{"x":0.0743408203125,"y":0.17273712158203125},{"x":0.270111083984375,"y":0.02104949951171875},{"x":-3.96728515625E-4,"y":0.1979217529296875},{"x":0.23248291015625,"y":0.08506011962890625},{"x":0.07769775390625,"y":0.3311920166015625},{"x":-0.025360107421875,"y":-0.01139068603515625},{"x":-0.061431884765625,"y":0.037261962890625},{"x":0.05010986328125,"y":-0.20317840576171875},{"x":-0.115875244140625,"y":0.09200286865234375},{"x":-0.065765380859375,"y":0.28741455078125},{"x":-0.09033203125,"y":0.223876953125},{"x":0.290802001953125,"y":-2.0599365234375E-4},{"x":0.14031982421875,"y":0.17504119873046875},{"x":0.18072509765625,"y":0.1040802001953125},{"x":0.14361572265625,"y":0.08985137939453125},{"x":-0.22344970703125,"y":-0.0686798095703125},{"x":0.077911376953125,"y":-0.2711334228515625},{"x":0.304931640625,"y":-0.01483154296875},{"x":-0.035888671875,"y":-0.1466522216796875},{"x":-0.140533447265625,"y":-0.351837158203125},{"x":0.05084228515625,"y":-0.085205078125},{"x":0.04119873046875,"y":-0.2157135009765625},{"x":0.0465087890625,"y":-0.371246337890625},{"x":0.102447509765625,"y":-0.438201904296875},{"x":0.20965576171875,"y":-0.1408843994140625},{"x":-0.2076416015625,"y":0.1949462890625},{"x":-0.10162353515625,"y":0.088104248046875},{"x":-0.04156494140625,"y":0.0675811767578125},{"x":-0.104949951171875,"y":0.1765899658203125},{"x":0.067718505859375,"y":-0.011444091796875},{"x":0.017547607421875,"y":-0.00384521484375},{"x":-0.048248291015625,"y":0.1306304931640625},{"x":-0.032501220703125,"y":-0.1228790283203125},{"x":0.025970458984375,"y":0.189727783203125},{"x":0.165313720703125,"y":0.0963134765625},{"x":-0.067291259765625,"y":-0.134002685546875},{"x":0.089324951171875,"y":-0.152984619140625},{"x":0.06304931640625,"y":-0.1715545654296875},{"x":0.2528076171875,"y":-0.0713043212890625},{"x":-0.013946533203125,"y":0.1953887939453125},{"x":-0.149505615234375,"y":0.196319580078125},{"x":-0.132049560546875,"y":0.203948974609375},{"x":-0.058380126953125,"y":0.2400665283203125},{"x":-0.212677001953125,"y":0.0947113037109375},{"x":0.02752685546875,"y":-0.076202392578125},{"x":-0.051239013671875,"y":-0.03863525390625}],"optimisedCameraToObject":{"translation":{"x":-0.096837737680499,"y":-0.25878002721351046,"z":0.6416849956469183},"rotation":{"quaternion":{"W":0.9863494172504824,"X":0.14672803691539432,"Y":-0.06638197767952948,"Z":0.03433865623379574}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":524.0452880859375,"y":49.90778350830078},{"x":548.7825317382812,"y":51.85581970214844},{"x":573.2677612304688,"y":53.88032531738281},{"x":598.1990356445312,"y":55.99870681762695},{"x":622.95849609375,"y":57.948421478271484},{"x":647.7489013671875,"y":59.852638244628906},{"x":672.5323486328125,"y":62.127445220947266},{"x":520.9467163085938,"y":75.27804565429688},{"x":544.95703125,"y":77.77095031738281},{"x":569.5671997070312,"y":79.86370086669922},{"x":594.2412109375,"y":81.78543853759766},{"x":618.8273315429688,"y":83.9392318725586},{"x":643.5252075195312,"y":86.03004455566406},{"x":668.039306640625,"y":87.96307373046875},{"x":517.3387451171875,"y":100.85692596435547},{"x":541.7862548828125,"y":102.91368865966797},{"x":565.7620849609375,"y":105.14532470703125},{"x":590.145263671875,"y":107.07211303710938},{"x":614.6468505859375,"y":108.95285034179688},{"x":639.0621948242188,"y":111.45539093017578},{"x":663.558837890625,"y":113.44426727294922},{"x":514.1788330078125,"y":125.99434661865234},{"x":538.1118774414062,"y":128.0659942626953},{"x":562.1294555664062,"y":130.11351013183594},{"x":586.357666015625,"y":132.17626953125},{"x":610.55517578125,"y":134.09750366210938},{"x":634.9482421875,"y":136.2822265625},{"x":659.05615234375,"y":138.57904052734375},{"x":511.08636474609375,"y":150.25636291503906},{"x":534.8436889648438,"y":151.9950408935547},{"x":558.8811645507812,"y":154.31716918945312},{"x":582.5707397460938,"y":156.5441131591797},{"x":606.7430419921875,"y":158.36708068847656},{"x":630.9149169921875,"y":160.6362762451172},{"x":654.8162231445312,"y":162.92947387695312},{"x":507.9510498046875,"y":174.54354858398438},{"x":531.57568359375,"y":176.43170166015625},{"x":555.1544799804688,"y":178.55892944335938},{"x":578.988525390625,"y":180.92955017089844},{"x":602.6702270507812,"y":182.96897888183594},{"x":626.5747680664062,"y":185.0165557861328},{"x":650.6617431640625,"y":187.2545166015625},{"x":504.9621887207031,"y":197.81924438476562},{"x":528.2085571289062,"y":200.1539306640625},{"x":551.8722534179688,"y":202.26214599609375},{"x":575.1571655273438,"y":204.21932983398438},{"x":599.0906372070312,"y":206.48681640625},{"x":622.7322998046875,"y":208.94635009765625},{"x":646.386474609375,"y":210.84791564941406}],"reprojectionErrors":[{"x":-0.201416015625,"y":-0.21646881103515625},{"x":-0.265625,"y":-0.116241455078125},{"x":-0.0078125,"y":-0.08187103271484375},{"x":-0.12969970703125,"y":-0.1310577392578125},{"x":-0.0172119140625,"y":-0.00154876708984375},{"x":0.12298583984375,"y":0.1831817626953125},{"x":0.324951171875,"y":0.006744384765625},{"x":-0.35345458984375,"y":0.22519683837890625},{"x":0.08233642578125,"y":-0.1977996826171875},{"x":-0.01287841796875,"y":-0.211456298828125},{"x":-0.106689453125,"y":-0.0452117919921875},{"x":-0.051025390625,"y":-0.10243988037109375},{"x":-0.0494384765625,"y":-0.088409423828125},{"x":0.18994140625,"y":0.0913848876953125},{"x":0.06048583984375,"y":-7.32421875E-4},{"x":-0.16412353515625,"y":0.032928466796875},{"x":0.15069580078125,"y":-0.10047149658203125},{"x":0.122314453125,"y":0.07846832275390625},{"x":0.0361328125,"y":0.31066131591796875},{"x":0.093017578125,"y":-0.0720672607421875},{"x":0.1217041015625,"y":0.0654296875},{"x":0.08160400390625,"y":-0.233245849609375},{"x":0.15185546875,"y":-0.19503021240234375},{"x":0.20428466796875,"y":-0.1262054443359375},{"x":0.1092529296875,"y":-0.0664825439453125},{"x":0.1044921875,"y":0.1406402587890625},{"x":-0.03985595703125,"y":0.08978271484375},{"x":0.1531982421875,"y":-0.0679473876953125},{"x":0.089202880859375,"y":-0.0277862548828125},{"x":0.119140625,"y":0.3618011474609375},{"x":-0.06536865234375,"y":0.1731109619140625},{"x":0.16009521484375,"y":0.08447265625},{"x":-0.0384521484375,"y":0.40435791015625},{"x":-0.18145751953125,"y":0.2822418212890625},{"x":-0.00244140625,"y":0.1400299072265625},{"x":0.192291259765625,"y":-0.274688720703125},{"x":0.14239501953125,"y":-0.0171661376953125},{"x":0.20294189453125,"y":0.0052032470703125},{"x":0.0694580078125,"y":-0.2122039794921875},{"x":0.14605712890625,"y":-0.0951385498046875},{"x":0.05401611328125,"y":0.0167388916015625},{"x":-0.169677734375,"y":-0.0591278076171875},{"x":0.20037841796875,"y":0.07269287109375},{"x":0.319580078125,"y":-0.0998687744140625},{"x":0.0850830078125,"y":-0.043243408203125},{"x":0.28961181640625,"y":0.16680908203125},{"x":-0.0975341796875,"y":0.0686187744140625},{"x":-0.1395263671875,"y":-0.2198638916015625},{"x":-0.14404296875,"y":0.051025390625}],"optimisedCameraToObject":{"translation":{"x":0.11180230078923507,"y":-0.2899533474899091,"z":0.6979758686890563},"rotation":{"quaternion":{"W":0.9906162757454453,"X":0.1258582013803331,"Y":0.02622597805862725,"Z":0.046382167353411295}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":569.9073486328125,"y":73.99394226074219},{"x":593.7904663085938,"y":73.92759704589844},{"x":617.990966796875,"y":73.24340057373047},{"x":643.0416259765625,"y":73.14846801757812},{"x":668.4610595703125,"y":72.73075866699219},{"x":694.3900146484375,"y":72.2044677734375},{"x":720.5175170898438,"y":72.14366912841797},{"x":568.0505981445312,"y":98.00820922851562},{"x":591.8472900390625,"y":97.92613220214844},{"x":615.986572265625,"y":97.81549835205078},{"x":640.8120727539062,"y":97.73292541503906},{"x":665.9505615234375,"y":97.5985336303711},{"x":691.6508178710938,"y":97.54235076904297},{"x":717.8319702148438,"y":97.50757598876953},{"x":565.9100952148438,"y":121.66460418701172},{"x":589.5657958984375,"y":122.00975036621094},{"x":613.7761840820312,"y":121.93992614746094},{"x":638.0863647460938,"y":122.02753448486328},{"x":663.0403442382812,"y":122.1830062866211},{"x":688.5869140625,"y":122.5542984008789},{"x":714.6636352539062,"y":122.8083267211914},{"x":563.9707641601562,"y":145.3894805908203},{"x":587.3191528320312,"y":145.67210388183594},{"x":611.2584228515625,"y":145.91616821289062},{"x":635.7897338867188,"y":146.11669921875},{"x":660.3165893554688,"y":146.7986602783203},{"x":686.0416259765625,"y":147.0889892578125},{"x":711.6866455078125,"y":147.6366729736328},{"x":562.1524658203125,"y":167.92236328125},{"x":585.6284790039062,"y":168.77854919433594},{"x":608.9248046875,"y":169.30848693847656},{"x":633.28759765625,"y":169.87631225585938},{"x":658.009521484375,"y":170.32583618164062},{"x":683.282470703125,"y":171.13014221191406},{"x":708.7063598632812,"y":171.9752197265625},{"x":560.1513061523438,"y":191.0990447998047},{"x":583.4462890625,"y":191.87060546875},{"x":606.9073486328125,"y":192.7923126220703},{"x":631.0411376953125,"y":193.55857849121094},{"x":655.4586791992188,"y":194.24212646484375},{"x":680.503662109375,"y":195.13235473632812},{"x":706.0552368164062,"y":196.1321258544922},{"x":558.7040405273438,"y":213.17831420898438},{"x":581.2661743164062,"y":214.52236938476562},{"x":604.6900024414062,"y":215.52694702148438},{"x":628.9173583984375,"y":216.232177734375},{"x":653.1513671875,"y":217.75714111328125},{"x":677.8412475585938,"y":218.7955322265625},{"x":702.9755249023438,"y":219.9374542236328}],"reprojectionErrors":[{"x":-0.2523193359375,"y":-0.05484771728515625},{"x":-0.2550048828125,"y":-0.28891754150390625},{"x":-0.06915283203125,"y":0.09384918212890625},{"x":-0.21514892578125,"y":-0.11365509033203125},{"x":-0.19873046875,"y":6.256103515625E-4},{"x":-0.14752197265625,"y":0.22251129150390625},{"x":0.26318359375,"y":-0.0220489501953125},{"x":-0.2667236328125,"y":-0.1227874755859375},{"x":-0.35626220703125,"y":-0.08994293212890625},{"x":-0.289306640625,"y":-0.02548980712890625},{"x":-0.39739990234375,"y":0.01406097412109375},{"x":-0.29461669921875,"y":0.1086883544921875},{"x":-0.2169189453125,"y":0.12847900390625},{"x":-0.07012939453125,"y":0.1303558349609375},{"x":0.02716064453125,"y":-0.13533782958984375},{"x":-0.09259033203125,"y":-0.284881591796875},{"x":-0.27459716796875,"y":-0.01250457763671875},{"x":-0.0521240234375,"y":0.10958099365234375},{"x":0.04302978515625,"y":0.171142578125},{"x":0.0748291015625,"y":0.02442169189453125},{"x":0.11859130859375,"y":0.00270843505859375},{"x":0.14404296875,"y":-0.5141754150390625},{"x":0.16253662109375,"y":-0.362548828125},{"x":0.07598876953125,"y":-0.16168212890625},{"x":-0.105224609375,"y":0.09368896484375},{"x":0.22747802734375,"y":-0.1211395263671875},{"x":-0.1162109375,"y":0.0671844482421875},{"x":0.15460205078125,"y":0.0099639892578125},{"x":0.16363525390625,"y":0.005767822265625},{"x":-0.11248779296875,"y":-0.183563232421875},{"x":0.2703857421875,"y":-0.0323638916015625},{"x":0.0775146484375,"y":0.095550537109375},{"x":0.0279541015625,"y":0.3567352294921875},{"x":-0.05810546875,"y":0.278472900390625},{"x":0.23187255859375,"y":0.1751251220703125},{"x":0.38958740234375,"y":-0.4068145751953125},{"x":0.12945556640625,"y":-0.2847900390625},{"x":0.17620849609375,"y":-0.2952117919921875},{"x":0.03436279296875,"y":-0.132080078125},{"x":0.10443115234375,"y":0.1323089599609375},{"x":0.05438232421875,"y":0.208984375},{"x":0.017333984375,"y":0.1955413818359375},{"x":0.08465576171875,"y":-0.00628662109375},{"x":0.39434814453125,"y":-0.2357635498046875},{"x":0.30908203125,"y":-0.1047821044921875},{"x":-0.10211181640625,"y":0.3470001220703125},{"x":-0.031005859375,"y":9.918212890625E-4},{"x":0.0845947265625,"y":0.164031982421875},{"x":0.26812744140625,"y":0.246490478515625}],"optimisedCameraToObject":{"translation":{"x":0.17138264525875638,"y":-0.2813007452027751,"z":0.7539567728267917},"rotation":{"quaternion":{"W":0.9827523221429988,"X":0.09195102006070209,"Y":0.15738290927159682,"Z":0.031201011226373154}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":54.021060943603516,"y":345.8491516113281},{"x":80.6604232788086,"y":347.9986877441406},{"x":107.37610626220703,"y":350.2543029785156},{"x":134.38453674316406,"y":352.951171875},{"x":161.2216339111328,"y":355.3465270996094},{"x":188.6256103515625,"y":357.83685302734375},{"x":215.398681640625,"y":360.0675048828125},{"x":52.778690338134766,"y":373.049072265625},{"x":79.32679748535156,"y":375.1228942871094},{"x":105.89820098876953,"y":377.8143005371094},{"x":132.64906311035156,"y":380.1212158203125},{"x":159.46510314941406,"y":382.7596130371094},{"x":186.77223205566406,"y":385.237060546875},{"x":213.88624572753906,"y":387.6988830566406},{"x":51.31965255737305,"y":400.0137939453125},{"x":77.89776611328125,"y":402.0867004394531},{"x":104.51695251464844,"y":404.90045166015625},{"x":131.23776245117188,"y":407.3962707519531},{"x":157.92202758789062,"y":409.95086669921875},{"x":184.858642578125,"y":412.3852233886719},{"x":211.6796875,"y":415.0224914550781},{"x":50.216064453125,"y":426.903564453125},{"x":76.48403930664062,"y":429.3251953125},{"x":102.92842864990234,"y":431.9815979003906},{"x":129.36061096191406,"y":434.6663818359375},{"x":156.23484802246094,"y":437.089111328125},{"x":183.0674591064453,"y":439.8330078125},{"x":209.96823120117188,"y":442.1966857910156},{"x":49.0931282043457,"y":453.1805725097656},{"x":75.02845001220703,"y":455.94610595703125},{"x":101.50030517578125,"y":458.5848388671875},{"x":127.96678161621094,"y":461.2262878417969},{"x":154.43560791015625,"y":463.8559265136719},{"x":181.41050720214844,"y":466.3123474121094},{"x":208.05648803710938,"y":469.11468505859375},{"x":47.83256912231445,"y":479.9390869140625},{"x":72.99527740478516,"y":482.4075012207031},{"x":99.99420166015625,"y":485.33514404296875},{"x":126.40711975097656,"y":488.1174621582031},{"x":152.93824768066406,"y":490.9019470214844},{"x":179.83306884765625,"y":493.5959167480469},{"x":206.09521484375,"y":496.2043151855469},{"x":46.79403305053711,"y":506.0128479003906},{"x":72.34687042236328,"y":508.8729553222656},{"x":98.41320037841797,"y":511.9922180175781},{"x":124.83399200439453,"y":514.6483154296875},{"x":151.21229553222656,"y":517.3984375},{"x":177.8666534423828,"y":520.215087890625},{"x":204.25149536132812,"y":523.1304931640625}],"reprojectionErrors":[{"x":0.15678024291992188,"y":-0.183197021484375},{"x":0.02092742919921875,"y":0.0977783203125},{"x":-0.04419708251953125,"y":0.278961181640625},{"x":-0.2590179443359375,"y":0.02471923828125},{"x":-0.163543701171875,"y":0.077392578125},{"x":-0.5001983642578125,"y":0.040130615234375},{"x":-0.0754241943359375,"y":0.26708984375},{"x":0.010646820068359375,"y":-0.253173828125},{"x":-0.10228729248046875,"y":0.161956787109375},{"x":-0.09206390380859375,"y":-0.03564453125},{"x":-0.1188201904296875,"y":0.1556396484375},{"x":-0.072357177734375,"y":0.01934814453125},{"x":-0.38275146484375,"y":0.04754638671875},{"x":-0.370025634765625,"y":0.0943603515625},{"x":0.09525299072265625,"y":-0.223052978515625},{"x":-0.1161651611328125,"y":0.250823974609375},{"x":-0.2227935791015625,"y":-0.01275634765625},{"x":-0.2891387939453125,"y":0.0445556640625},{"x":-0.18109130859375,"y":0.0455322265625},{"x":-0.1916961669921875,"y":0.16876220703125},{"x":0.0427398681640625,"y":0.09063720703125},{"x":-0.16155242919921875,"y":-0.25360107421875},{"x":-0.131439208984375,"y":-0.0712890625},{"x":-0.1324615478515625,"y":-0.12176513671875},{"x":0.0200347900390625,"y":-0.199127197265625},{"x":-0.1322174072265625,"y":-0.013427734375},{"x":-0.10968017578125,"y":-0.14837646484375},{"x":-0.0263519287109375,"y":0.096954345703125},{"x":-0.3849906921386719,"y":0.1925048828125},{"x":-0.09095001220703125,"y":0.087432861328125},{"x":-0.1887664794921875,"y":0.109710693359375},{"x":-0.14046478271484375,"y":0.12933349609375},{"x":0.042236328125,"y":0.16033935546875},{"x":-0.1485137939453125,"y":0.3636474609375},{"x":0.1180877685546875,"y":0.2196044921875},{"x":-0.456817626953125,"y":0.020477294921875},{"x":0.540985107421875,"y":0.268341064453125},{"x":-0.153350830078125,"y":0.056182861328125},{"x":-0.1215057373046875,"y":-0.01202392578125},{"x":-0.071685791015625,"y":-0.084259033203125},{"x":-0.2534942626953125,"y":-0.068328857421875},{"x":0.3253173828125,"y":0.0302734375},{"x":-0.7367134094238281,"y":0.396087646484375},{"x":-0.19800567626953125,"y":0.307464599609375},{"x":-0.02930450439453125,"y":-0.04254150390625},{"x":-0.075469970703125,"y":0.06793212890625},{"x":0.05645751953125,"y":0.0810546875},{"x":0.04388427734375,"y":0.02386474609375},{"x":0.4282379150390625,"y":-0.136474609375}],"optimisedCameraToObject":{"translation":{"x":-0.3376944754930934,"y":0.010670399215407439,"z":0.6308653198319402},"rotation":{"quaternion":{"W":0.9982657804214611,"X":0.029791771900953612,"Y":0.029229776026813533,"Z":0.04151508352340248}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":169.9084014892578,"y":379.78753662109375},{"x":196.73521423339844,"y":382.94451904296875},{"x":223.49105834960938,"y":386.1179504394531},{"x":250.33724975585938,"y":389.3939208984375},{"x":277.0940246582031,"y":392.5008544921875},{"x":303.8894958496094,"y":395.5666198730469},{"x":330.424072265625,"y":398.856689453125},{"x":167.05535888671875,"y":406.4210205078125},{"x":193.77183532714844,"y":409.4658203125},{"x":220.65167236328125,"y":412.78973388671875},{"x":247.35498046875,"y":416.1004943847656},{"x":273.9166564941406,"y":419.171630859375},{"x":300.79022216796875,"y":422.2829284667969},{"x":327.4206237792969,"y":425.6172180175781},{"x":164.34991455078125,"y":432.7615661621094},{"x":190.96731567382812,"y":435.82049560546875},{"x":217.72662353515625,"y":438.82293701171875},{"x":244.43817138671875,"y":441.98480224609375},{"x":270.94586181640625,"y":445.5509033203125},{"x":297.7475891113281,"y":448.7810974121094},{"x":324.2535400390625,"y":451.9615173339844},{"x":161.87857055664062,"y":459.0615234375},{"x":188.09515380859375,"y":462.1319274902344},{"x":214.9080352783203,"y":465.37811279296875},{"x":241.51596069335938,"y":468.8562316894531},{"x":268.1548156738281,"y":471.958740234375},{"x":294.5619812011719,"y":475.14068603515625},{"x":321.0926513671875,"y":478.1224365234375},{"x":159.09461975097656,"y":485.0336608886719},{"x":185.63937377929688,"y":488.1323547363281},{"x":212.0060272216797,"y":491.2232360839844},{"x":238.78387451171875,"y":494.78778076171875},{"x":265.02703857421875,"y":497.9711608886719},{"x":291.7558898925781,"y":501.07452392578125},{"x":317.98138427734375,"y":504.1951904296875},{"x":156.3255615234375,"y":511.2371826171875},{"x":182.9231719970703,"y":514.3885498046875},{"x":209.1217498779297,"y":517.6865234375},{"x":235.95286560058594,"y":520.790771484375},{"x":262.50238037109375,"y":524.3716430664062},{"x":288.48516845703125,"y":527.1818237304688},{"x":315.14971923828125,"y":530.8562622070312},{"x":153.8773193359375,"y":536.93212890625},{"x":180.115966796875,"y":540.3148193359375},{"x":206.3045196533203,"y":543.87158203125},{"x":232.95066833496094,"y":546.8753662109375},{"x":259.12579345703125,"y":550.2133178710938},{"x":285.5578918457031,"y":553.22021484375},{"x":311.8815612792969,"y":556.64306640625}],"reprojectionErrors":[{"x":0.0184478759765625,"y":-0.13311767578125},{"x":-0.0904693603515625,"y":-0.03399658203125},{"x":-0.10821533203125,"y":0.042572021484375},{"x":-0.2010650634765625,"y":0.009918212890625},{"x":-0.194183349609375,"y":0.13897705078125},{"x":-0.220611572265625,"y":0.30133056640625},{"x":0.014251708984375,"y":0.230865478515625},{"x":0.1129302978515625,"y":-0.2142333984375},{"x":0.058746337890625,"y":-0.004974365234375},{"x":-0.1385040283203125,"y":-0.08258056640625},{"x":-0.143829345703125,"y":-0.15533447265625},{"x":0.002960205078125,"y":0.00262451171875},{"x":-0.156585693359375,"y":0.11090087890625},{"x":-0.0723876953125,"y":-0.013916015625},{"x":0.0755615234375,"y":-0.11480712890625},{"x":0.0645751953125,"y":0.07818603515625},{"x":-0.067901611328125,"y":0.318328857421875},{"x":-0.1371002197265625,"y":0.389129638671875},{"x":0.008209228515625,"y":0.045166015625},{"x":-0.13482666015625,"y":0.0260009765625},{"x":0.01873779296875,"y":0.044921875},{"x":-0.1800994873046875,"y":-0.08795166015625},{"x":0.1535797119140625,"y":0.091339111328125},{"x":-0.0884857177734375,"y":0.083953857421875},{"x":-0.109954833984375,"y":-0.166900634765625},{"x":-0.151580810546875,"y":-0.054229736328125},{"x":0.044403076171875,"y":-0.033721923828125},{"x":0.11785888671875,"y":0.173736572265625},{"x":-0.1072998046875,"y":0.152740478515625},{"x":-0.1581878662109375,"y":0.301483154296875},{"x":-0.01031494140625,"y":0.445526123046875},{"x":-0.25787353515625,"y":0.10284423828125},{"x":0.040191650390625,"y":0.12762451171875},{"x":-0.141357421875,"y":0.2181396484375},{"x":0.181640625,"y":0.276519775390625},{"x":-0.033477783203125,"y":0.04736328125},{"x":-0.193878173828125,"y":0.14105224609375},{"x":0.065521240234375,"y":0.07415771484375},{"x":-0.291717529296875,"y":0.186279296875},{"x":-0.35626220703125,"y":-0.1934814453125},{"x":0.15216064453125,"y":0.181640625},{"x":-0.019805908203125,"y":-0.32391357421875},{"x":-0.2645263671875,"y":0.33514404296875},{"x":-0.1228485107421875,"y":0.19512939453125},{"x":0.08978271484375,"y":-0.13458251953125},{"x":-0.13916015625,"y":0.07244873046875},{"x":0.114166259765625,"y":-0.0714111328125},{"x":0.116912841796875,"y":0.098388671875},{"x":0.22967529296875,"y":-0.16571044921875}],"optimisedCameraToObject":{"translation":{"x":-0.23276045132651585,"y":0.04247056910912708,"z":0.6401151758906024},"rotation":{"quaternion":{"W":0.9978415297651868,"X":0.026492084004514294,"Y":0.002260344468967054,"Z":0.06004449853109906}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":191.27963256835938,"y":216.85125732421875},{"x":218.47052001953125,"y":217.94668579101562},{"x":245.47113037109375,"y":219.14886474609375},{"x":272.6984558105469,"y":220.8357696533203},{"x":299.729248046875,"y":221.94078063964844},{"x":326.26116943359375,"y":223.40304565429688},{"x":352.9256286621094,"y":224.6544189453125},{"x":189.86184692382812,"y":243.27569580078125},{"x":217.16983032226562,"y":244.93350219726562},{"x":244.09861755371094,"y":246.04212951660156},{"x":271.1670227050781,"y":247.20339965820312},{"x":297.96771240234375,"y":248.6288299560547},{"x":324.9637756347656,"y":249.87075805664062},{"x":351.7329406738281,"y":251.30844116210938},{"x":188.1334228515625,"y":270.4233093261719},{"x":215.7362518310547,"y":271.6968994140625},{"x":242.74481201171875,"y":273.0059509277344},{"x":269.8470153808594,"y":274.04656982421875},{"x":296.7548522949219,"y":275.5838317871094},{"x":323.8454895019531,"y":276.5580749511719},{"x":350.08319091796875,"y":278.0265808105469},{"x":186.9500274658203,"y":297.47869873046875},{"x":214.30479431152344,"y":298.7670593261719},{"x":241.24801635742188,"y":300.0479431152344},{"x":268.4455261230469,"y":301.0298156738281},{"x":295.320068359375,"y":302.075439453125},{"x":322.00225830078125,"y":303.5672302246094},{"x":348.958740234375,"y":304.5511169433594},{"x":185.1971435546875,"y":324.2554626464844},{"x":212.70465087890625,"y":325.37811279296875},{"x":239.93789672851562,"y":326.5377502441406},{"x":267.06201171875,"y":327.84759521484375},{"x":294.1334228515625,"y":328.8582458496094},{"x":320.9775085449219,"y":330.0740661621094},{"x":347.8205261230469,"y":331.12750244140625},{"x":183.9181671142578,"y":351.8352966308594},{"x":211.31854248046875,"y":352.7696838378906},{"x":238.3460693359375,"y":353.86358642578125},{"x":265.9459533691406,"y":354.92620849609375},{"x":292.6164245605469,"y":356.06585693359375},{"x":319.7096862792969,"y":357.0189208984375},{"x":346.3279724121094,"y":358.3317565917969},{"x":182.28382873535156,"y":378.80584716796875},{"x":209.72714233398438,"y":379.8011169433594},{"x":236.80055236816406,"y":380.6304931640625},{"x":264.05438232421875,"y":381.9520568847656},{"x":290.985595703125,"y":382.8981018066406},{"x":318.15606689453125,"y":384.01708984375},{"x":344.934814453125,"y":385.1326904296875}],"reprojectionErrors":[{"x":0.091766357421875,"y":-0.204681396484375},{"x":0.002960205078125,"y":0.048980712890625},{"x":0.0292205810546875,"y":0.1986846923828125},{"x":-0.25103759765625,"y":-0.1338348388671875},{"x":-0.419097900390625,"y":0.1177978515625},{"x":-0.1771240234375,"y":0.0141754150390625},{"x":-0.160919189453125,"y":0.123199462890625},{"x":-0.004638671875,"y":0.146148681640625},{"x":-0.1624298095703125,"y":-0.2011260986328125},{"x":-0.01641845703125,"y":0.0020294189453125},{"x":-0.09002685546875,"y":0.1535491943359375},{"x":0.01953125,"y":0.04168701171875},{"x":-0.155364990234375,"y":0.113861083984375},{"x":-0.19683837890625,"y":-0.0094451904296875},{"x":0.2077484130859375,"y":-0.134246826171875},{"x":-0.197113037109375,"y":-0.13616943359375},{"x":-0.0832977294921875,"y":-0.173828125},{"x":-0.143310546875,"y":0.056427001953125},{"x":-0.09375,"y":-0.210662841796875},{"x":-0.3162841796875,"y":0.084320068359375},{"x":0.22039794921875,"y":-0.11614990234375},{"x":-0.1266326904296875,"y":-0.231536865234375},{"x":-0.23602294921875,"y":-0.287384033203125},{"x":-0.0096282958984375,"y":-0.33758544921875},{"x":-0.117919921875,"y":-0.090789794921875},{"x":0.011749267578125,"y":0.090057373046875},{"x":0.2442626953125,"y":-0.177734375},{"x":0.1085205078125,"y":0.059722900390625},{"x":0.1067962646484375,"y":0.039642333984375},{"x":-0.1082763671875,"y":0.110015869140625},{"x":-0.125030517578125,"y":0.14007568359375},{"x":-0.113250732421875,"y":0.016387939453125},{"x":-0.13397216796875,"y":0.188140869140625},{"x":-0.01708984375,"y":0.150787353515625},{"x":0.006622314453125,"y":0.271697998046875},{"x":-0.135284423828125,"y":-0.403564453125},{"x":-0.196533203125,"y":-0.18463134765625},{"x":0.0389556884765625,"y":-0.130126953125},{"x":-0.378692626953125,"y":-0.0494384765625},{"x":0.047637939453125,"y":-0.051025390625},{"x":-0.03875732421875,"y":0.128509521484375},{"x":0.255340576171875,"y":-0.057373046875},{"x":-0.023529052734375,"y":-0.14984130859375},{"x":-0.0813751220703125,"y":-0.031829833984375},{"x":0.1544036865234375,"y":0.24560546875},{"x":0.128753662109375,"y":0.024200439453125},{"x":0.340118408203125,"y":0.171539306640625},{"x":0.2220458984375,"y":0.13897705078125},{"x":0.4010009765625,"y":0.1026611328125}],"optimisedCameraToObject":{"translation":{"x":-0.2150847523788902,"y":-0.10937536181850693,"z":0.6429841641418208},"rotation":{"quaternion":{"W":0.9993159980263666,"X":-0.020445743598099413,"Y":-0.021328105240713092,"Z":0.02224004460716604}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":59.23370361328125,"y":38.33932113647461},{"x":87.00922393798828,"y":42.854488372802734},{"x":115.02725982666016,"y":47.634586334228516},{"x":143.60504150390625,"y":52.71324157714844},{"x":171.82850646972656,"y":57.26994705200195},{"x":200.09176635742188,"y":62.67976760864258},{"x":228.7822265625,"y":67.39237976074219},{"x":58.10192108154297,"y":68.38838195800781},{"x":85.84864044189453,"y":73.02838897705078},{"x":113.53894805908203,"y":78.06898498535156},{"x":141.32225036621094,"y":82.71914672851562},{"x":169.2020263671875,"y":87.6176528930664},{"x":197.4345703125,"y":92.37641143798828},{"x":225.79214477539062,"y":97.39598846435547},{"x":56.9709358215332,"y":97.74823760986328},{"x":84.2510757446289,"y":102.57099914550781},{"x":111.88727569580078,"y":107.37693786621094},{"x":139.54527282714844,"y":112.22335052490234},{"x":167.1638946533203,"y":117.38727569580078},{"x":195.0981903076172,"y":121.94737243652344},{"x":222.89840698242188,"y":127.00836944580078},{"x":56.05445861816406,"y":126.9969482421875},{"x":83.18038177490234,"y":131.7643280029297},{"x":110.25074768066406,"y":136.32122802734375},{"x":137.76243591308594,"y":141.2616424560547},{"x":165.10943603515625,"y":146.13067626953125},{"x":192.70748901367188,"y":151.25067138671875},{"x":220.0210723876953,"y":155.9210968017578},{"x":55.16352462768555,"y":154.84536743164062},{"x":81.90992736816406,"y":159.82772827148438},{"x":107.75545501708984,"y":164.19235229492188},{"x":136.01239013671875,"y":169.29620361328125},{"x":162.9975128173828,"y":174.12254333496094},{"x":190.13108825683594,"y":179.03558349609375},{"x":217.07798767089844,"y":183.92031860351562},{"x":54.216739654541016,"y":182.7169189453125},{"x":80.44190216064453,"y":187.70164489746094},{"x":107.44196319580078,"y":192.23924255371094},{"x":134.1920166015625,"y":197.17784118652344},{"x":160.91378784179688,"y":202.044921875},{"x":187.84996032714844,"y":206.74261474609375},{"x":214.6104278564453,"y":211.8448486328125},{"x":53.25253677368164,"y":209.8740692138672},{"x":79.40377044677734,"y":214.40386962890625},{"x":105.58558654785156,"y":219.63250732421875},{"x":132.1798858642578,"y":224.1912841796875},{"x":158.90245056152344,"y":228.87069702148438},{"x":185.24468994140625,"y":233.74179077148438},{"x":211.927001953125,"y":238.5734405517578}],"reprojectionErrors":[{"x":-0.317718505859375,"y":-0.3343505859375},{"x":-0.0537567138671875,"y":-0.004772186279296875},{"x":0.0700836181640625,"y":0.0789031982421875},{"x":-0.2684173583984375,"y":-0.1178131103515625},{"x":-0.1602630615234375,"y":0.22472000122070312},{"x":-0.00469970703125,"y":-0.26944732666015625},{"x":-0.1942901611328125,"y":-0.05088043212890625},{"x":-0.23468017578125,"y":-0.15471649169921875},{"x":-0.252471923828125,"y":0.039794921875},{"x":-0.1133575439453125,"y":-0.1494140625},{"x":0.028350830078125,"y":0.0678253173828125},{"x":0.1642303466796875,"y":0.0518798828125},{"x":0.032958984375,"y":0.18994903564453125},{"x":-0.14276123046875,"y":0.08058929443359375},{"x":-0.1221466064453125,"y":0.05649566650390625},{"x":0.0223846435546875,"y":0.057220458984375},{"x":-0.09051513671875,"y":0.08957672119140625},{"x":-0.131378173828125,"y":0.09540557861328125},{"x":-0.043853759765625,"y":-0.20318603515625},{"x":-0.18792724609375,"y":0.1142730712890625},{"x":-0.1187896728515625,"y":-0.05783843994140625},{"x":-0.19474411010742188,"y":-0.25917816162109375},{"x":-0.19415283203125,"y":-0.21484375},{"x":-0.0411834716796875,"y":0.05279541015625},{"x":-0.237396240234375,"y":-0.051116943359375},{"x":-0.1815338134765625,"y":-0.0725250244140625},{"x":-0.29412841796875,"y":-0.3346710205078125},{"x":-0.044525146484375,"y":-0.1378631591796875},{"x":-0.2644004821777344,"y":0.206268310546875},{"x":-0.1765289306640625,"y":0.023162841796875},{"x":0.9072952270507812,"y":0.4687042236328125},{"x":-0.3298187255859375,"y":0.1850738525390625},{"x":-0.2092742919921875,"y":0.18817138671875},{"x":-0.1560516357421875,"y":0.1129150390625},{"x":0.16021728515625,"y":0.073455810546875},{"x":-0.2505683898925781,"y":0.0474853515625},{"x":0.072052001953125,"y":-0.151092529296875},{"x":-0.28685760498046875,"y":0.106536865234375},{"x":-0.306884765625,"y":-0.0286102294921875},{"x":-0.2143096923828125,"y":-0.0848541259765625},{"x":-0.2564239501953125,"y":0.0348358154296875},{"x":-0.0477752685546875,"y":-0.244354248046875},{"x":-0.19250106811523438,"y":0.0194549560546875},{"x":-0.0768585205078125,"y":0.2621002197265625},{"x":0.09990692138671875,"y":-0.186798095703125},{"x":-0.0485076904296875,"y":0.0406494140625},{"x":-0.242340087890625,"y":0.153106689453125},{"x":0.0225067138671875,"y":0.0786590576171875},{"x":0.02105712890625,"y":0.0475921630859375}],"optimisedCameraToObject":{"translation":{"x":-0.31398098365329796,"y":-0.26199779844573945,"z":0.5907639670993632},"rotation":{"quaternion":{"W":0.9872467645719031,"X":0.1304301838620576,"Y":0.02714312407484395,"Z":0.0871495484525126}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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.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.72689819335938,"y":33.15799331665039},{"x":263.7967529296875,"y":40.7578010559082},{"x":287.8833312988281,"y":48.0333251953125},{"x":311.61834716796875,"y":55.17482376098633},{"x":334.3671875,"y":62.214752197265625},{"x":357.2959289550781,"y":69.20870971679688},{"x":379.2075500488281,"y":75.70208740234375},{"x":234.3531494140625,"y":58.178619384765625},{"x":258.6037292480469,"y":65.50260925292969},{"x":282.2972106933594,"y":72.17964935302734},{"x":305.9635009765625,"y":79.34990692138672},{"x":328.97607421875,"y":86.25747680664062},{"x":351.84820556640625,"y":92.91856384277344},{"x":373.8199462890625,"y":99.42518615722656},{"x":253.5649871826172,"y":89.9132080078125},{"x":276.9542236328125,"y":96.32315826416016},{"x":300.2864990234375,"y":103.17231750488281},{"x":323.1972351074219,"y":109.72388458251953},{"x":345.8652648925781,"y":116.2955322265625},{"x":367.6835632324219,"y":122.4262924194336},{"x":248.2954559326172,"y":113.93680572509766},{"x":271.8513488769531,"y":120.30672454833984},{"x":294.8355712890625,"y":126.57392120361328},{"x":318.0011901855469,"y":133.02987670898438},{"x":340.1617126464844,"y":139.28271484375},{"x":362.13580322265625,"y":145.26304626464844},{"x":219.8536376953125,"y":130.91848754882812},{"x":243.47097778320312,"y":137.08999633789062},{"x":266.92474365234375,"y":143.48121643066406},{"x":289.93817138671875,"y":149.64295959472656},{"x":312.24273681640625,"y":155.601806640625},{"x":334.6473388671875,"y":161.81057739257812},{"x":356.7762756347656,"y":167.82608032226562},{"x":214.8106689453125,"y":154.2523956298828},{"x":238.4207000732422,"y":160.69053649902344},{"x":261.7353210449219,"y":166.7123565673828},{"x":284.6801452636719,"y":172.58462524414062},{"x":307.0385437011719,"y":178.3723907470703},{"x":329.4573974609375,"y":184.3551788330078},{"x":351.25018310546875,"y":190.03836059570312},{"x":210.06382751464844,"y":177.6529998779297},{"x":233.64175415039062,"y":183.278076171875},{"x":256.6298522949219,"y":189.24708557128906},{"x":279.5111083984375,"y":194.890625},{"x":302.297607421875,"y":200.62628173828125},{"x":324.1338195800781,"y":206.17138671875},{"x":345.5912170410156,"y":211.9669189453125}],"reprojectionErrors":[{"x":0.086334228515625,"y":0.33527374267578125},{"x":0.296661376953125,"y":0.07115936279296875},{"x":0.092559814453125,"y":0.015522003173828125},{"x":-0.151641845703125,"y":-0.020183563232421875},{"x":0.204559326171875,"y":-0.06673049926757812},{"x":9.765625E-4,"y":-0.17804718017578125},{"x":0.440399169921875,"y":0.10211944580078125},{"x":0.2983856201171875,"y":0.2153472900390625},{"x":0.19818115234375,"y":-0.02845001220703125},{"x":0.2625732421875,"y":0.26258087158203125},{"x":-0.032501220703125,"y":-0.05007171630859375},{"x":-0.054718017578125,"y":-0.2088775634765625},{"x":-0.3116455078125,"y":-0.2284393310546875},{"x":-0.037689208984375,"y":-0.199188232421875},{"x":0.020050048828125,"y":-0.14000701904296875},{"x":0.26483154296875,"y":0.172515869140625},{"x":0.18487548828125,"y":-0.0611419677734375},{"x":0.150390625,"y":-0.1026153564453125},{"x":-0.011871337890625,"y":-0.26802825927734375},{"x":0.3106689453125,"y":-0.094879150390625},{"x":0.146026611328125,"y":-0.20459747314453125},{"x":0.101043701171875,"y":-0.0915985107421875},{"x":0.25091552734375,"y":0.02051544189453125},{"x":-0.151947021484375,"y":-0.1582183837890625},{"x":0.084442138671875,"y":-0.23443603515625},{"x":0.146759033203125,"y":-0.13726806640625},{"x":-0.249755859375,"y":0.087615966796875},{"x":-0.101043701171875,"y":0.267181396484375},{"x":-0.166229248046875,"y":0.1251983642578125},{"x":-0.163116455078125,"y":0.1123504638671875},{"x":0.182220458984375,"y":0.2034912109375},{"x":0.066162109375,"y":-0.0527496337890625},{"x":-0.130279541015625,"y":-0.2117462158203125},{"x":-0.081146240234375,"y":0.281585693359375},{"x":-0.0515594482421875,"y":-0.0366058349609375},{"x":-0.09918212890625,"y":-0.037139892578125},{"x":-0.144317626953125,"y":0.0146636962890625},{"x":0.034942626953125,"y":0.0551605224609375},{"x":-0.203155517578125,"y":-0.1938018798828125},{"x":-0.16693115234375,"y":-0.2361907958984375},{"x":-0.1399993896484375,"y":0.0806732177734375},{"x":-0.2039031982421875,"y":0.35009765625},{"x":-0.045806884765625,"y":0.180023193359375},{"x":-0.143524169921875,"y":0.2411956787109375},{"x":-0.5040283203125,"y":0.1174163818359375},{"x":-0.2667236328125,"y":0.092681884765625},{"x":0.001922607421875,"y":-0.2726593017578125}],"optimisedCameraToObject":{"translation":{"x":-0.1772052793529076,"y":-0.31064962242169675,"z":0.6964298094590401},"rotation":{"quaternion":{"W":0.980487576646583,"X":0.11542997233129565,"Y":-0.10535054120298924,"Z":0.11925307961450929}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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":629.2418823242188,"y":394.1077880859375},{"x":652.1565551757812,"y":395.2142028808594},{"x":674.8081665039062,"y":396.2560119628906},{"x":696.96484375,"y":397.7439880371094},{"x":719.1268310546875,"y":398.5635681152344},{"x":741.2089233398438,"y":399.87408447265625},{"x":626.5735473632812,"y":417.6573791503906},{"x":649.3732299804688,"y":418.90576171875},{"x":671.9674072265625,"y":419.70977783203125},{"x":694.2720947265625,"y":420.81756591796875},{"x":717.0031127929688,"y":421.7893371582031},{"x":738.462158203125,"y":422.5842590332031},{"x":759.8959350585938,"y":423.5893249511719},{"x":623.9418334960938,"y":440.7262268066406},{"x":646.517333984375,"y":441.8302001953125},{"x":669.081298828125,"y":442.8855285644531},{"x":691.0248413085938,"y":443.8077087402344},{"x":713.1117553710938,"y":444.478759765625},{"x":735.1264038085938,"y":445.4458312988281},{"x":756.6378173828125,"y":446.18804931640625},{"x":620.8837890625,"y":464.0538635253906},{"x":643.678466796875,"y":465.0412902832031},{"x":666.0115966796875,"y":465.7765808105469},{"x":688.1702880859375,"y":466.5329284667969},{"x":710.4564819335938,"y":467.65313720703125},{"x":732.0682983398438,"y":468.0877685546875},{"x":753.5613403320312,"y":468.8585510253906},{"x":618.0928344726562,"y":486.66046142578125},{"x":641.1178588867188,"y":486.632568359375},{"x":663.0654907226562,"y":488.0837707519531},{"x":685.4207763671875,"y":489.043212890625},{"x":707.2129516601562,"y":489.89117431640625},{"x":727.479248046875,"y":488.995361328125},{"x":750.6743774414062,"y":491.03582763671875},{"x":615.8975830078125,"y":509.5317687988281},{"x":637.9851684570312,"y":510.2052917480469},{"x":660.0061645507812,"y":510.9342346191406},{"x":682.269287109375,"y":511.4956970214844},{"x":704.420654296875,"y":512.0977783203125},{"x":726.2296752929688,"y":512.9381103515625},{"x":747.3182373046875,"y":512.0670166015625},{"x":613.0365600585938,"y":531.901611328125},{"x":635.4527587890625,"y":532.40478515625},{"x":657.7189331054688,"y":533.3848266601562},{"x":680.1582641601562,"y":533.1809692382812},{"x":701.40185546875,"y":534.449462890625},{"x":723.0699462890625,"y":535.0682983398438},{"x":744.3041381835938,"y":535.392333984375}],"reprojectionErrors":[{"x":0.18115234375,"y":0.1744384765625},{"x":0.07818603515625,"y":0.20147705078125},{"x":0.03546142578125,"y":0.274505615234375},{"x":0.2835693359375,"y":-0.1171875},{"x":0.3212890625,"y":0.1409912109375},{"x":0.2327880859375,"y":-0.110260009765625},{"x":0.10357666015625,"y":0.057861328125},{"x":0.03619384765625,"y":-0.155853271484375},{"x":-0.0269775390625,"y":0.0557861328125},{"x":-0.0030517578125,"y":-0.055267333984375},{"x":-0.6090087890625,"y":-0.0491943359375},{"x":-0.1474609375,"y":0.114959716796875},{"x":0.13385009765625,"y":0.05029296875},{"x":0.006103515625,"y":0.2325439453125},{"x":0.08367919921875,"y":0.065948486328125},{"x":-0.02691650390625,"y":-0.071380615234375},{"x":0.2821044921875,"y":-0.0948486328125},{"x":0.24578857421875,"y":0.11358642578125},{"x":0.0787353515625,"y":0.006927490234375},{"x":0.21112060546875,"y":0.106109619140625},{"x":0.3516845703125,"y":-0.039947509765625},{"x":0.1309814453125,"y":-0.185760498046875},{"x":0.17376708984375,"y":-0.099212646484375},{"x":0.1917724609375,"y":-0.053375244140625},{"x":-0.1181640625,"y":-0.39093017578125},{"x":0.04486083984375,"y":-0.062347412109375},{"x":0.1243896484375,"y":-0.089202880859375},{"x":0.44671630859375,"y":0.221343994140625},{"x":-0.0831298828125,"y":0.996551513671875},{"x":0.26788330078125,"y":0.27252197265625},{"x":0.01348876953125,"y":0.020263671875},{"x":0.1234130859375,"y":-0.140411376953125},{"x":1.55938720703125,"y":1.422943115234375},{"x":-0.13427734375,"y":0.0303955078125},{"x":-0.03741455078125,"y":0.031707763671875},{"x":0.29156494140625,"y":0.0126953125},{"x":0.4920654296875,"y":-0.082244873046875},{"x":0.25433349609375,"y":-0.03009033203125},{"x":-0.0689697265625,"y":-0.03875732421875},{"x":-0.2481689453125,"y":-0.3057861328125},{"x":0.09381103515625,"y":1.1187744140625},{"x":0.16070556640625,"y":0.15850830078125},{"x":0.08258056640625,"y":0.218505859375},{"x":-0.0389404296875,"y":-0.21929931640625},{"x":-0.5283203125,"y":0.506103515625},{"x":-0.01763916015625,"y":-0.26141357421875},{"x":-0.1282958984375,"y":-0.399658203125},{"x":-0.002685546875,"y":-0.2633056640625}],"optimisedCameraToObject":{"translation":{"x":0.22587121444809832,"y":0.06782473654955659,"z":0.7122782957843503},"rotation":{"quaternion":{"W":0.9960185650340947,"X":0.059174624276497376,"Y":-0.057065697846571985,"Z":0.03448025635696428}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":448.01922607421875,"y":429.3711242675781},{"x":472.0490417480469,"y":429.4726867675781},{"x":496.2168884277344,"y":429.271728515625},{"x":520.0890502929688,"y":429.09942626953125},{"x":543.7279663085938,"y":428.93798828125},{"x":566.9014892578125,"y":428.8719787597656},{"x":589.7700805664062,"y":428.5798034667969},{"x":446.55126953125,"y":454.0658264160156},{"x":470.9622497558594,"y":453.92071533203125},{"x":495.0009460449219,"y":453.31109619140625},{"x":519.0226440429688,"y":453.2720947265625},{"x":541.9225463867188,"y":453.7502136230469},{"x":565.2225341796875,"y":452.8781433105469},{"x":588.140380859375,"y":452.4361877441406},{"x":445.11834716796875,"y":478.656982421875},{"x":469.5306701660156,"y":477.9880676269531},{"x":493.20819091796875,"y":477.6735534667969},{"x":517.0267333984375,"y":477.4759216308594},{"x":540.4405517578125,"y":476.9804992675781},{"x":563.9301147460938,"y":476.72149658203125},{"x":586.2576904296875,"y":476.05255126953125},{"x":443.876220703125,"y":502.9913635253906},{"x":468.0343322753906,"y":502.4150390625},{"x":491.8365783691406,"y":501.8389587402344},{"x":515.945556640625,"y":501.2271728515625},{"x":539.0038452148438,"y":500.801025390625},{"x":562.118896484375,"y":500.0229797363281},{"x":584.1614990234375,"y":499.4252624511719},{"x":442.5850524902344,"y":526.896728515625},{"x":466.790283203125,"y":526.1390380859375},{"x":490.6747741699219,"y":525.6089477539062},{"x":514.0472412109375,"y":524.7410888671875},{"x":537.3267211914062,"y":523.8837890625},{"x":560.3927612304688,"y":523.137451171875},{"x":583.093017578125,"y":522.6951293945312},{"x":441.0116271972656,"y":550.9126586914062},{"x":465.08135986328125,"y":550.305908203125},{"x":488.9184265136719,"y":549.2070922851562},{"x":512.8445434570312,"y":548.2455444335938},{"x":535.8231811523438,"y":547.6776123046875},{"x":558.9379272460938,"y":546.9464111328125},{"x":581.3497314453125,"y":546.1129150390625},{"x":439.9410095214844,"y":574.75},{"x":463.8714599609375,"y":573.8395385742188},{"x":487.9673767089844,"y":572.8681030273438},{"x":511.12615966796875,"y":571.3697509765625},{"x":534.253662109375,"y":570.9132690429688},{"x":557.1595458984375,"y":570.0716552734375},{"x":579.8931274414062,"y":568.8884887695312}],"reprojectionErrors":[{"x":-0.24639892578125,"y":0.1151123046875},{"x":0.19097900390625,"y":-0.08154296875},{"x":0.179473876953125,"y":0.014434814453125},{"x":0.1544189453125,"y":0.072052001953125},{"x":0.05517578125,"y":0.10931396484375},{"x":0.11566162109375,"y":0.041839599609375},{"x":0.17724609375,"y":0.191375732421875},{"x":-0.066864013671875,"y":0.092620849609375},{"x":-0.09051513671875,"y":-0.007965087890625},{"x":-0.050567626953125,"y":0.346588134765625},{"x":-0.3006591796875,"y":0.121307373046875},{"x":0.265625,"y":-0.630035400390625},{"x":0.12823486328125,"y":-0.03997802734375},{"x":0.0711669921875,"y":0.111419677734375},{"x":0.084014892578125,"y":-0.007965087890625},{"x":-0.02069091796875,"y":0.266845703125},{"x":0.302825927734375,"y":0.1783447265625},{"x":0.180419921875,"y":-0.03570556640625},{"x":0.159423828125,"y":0.03955078125},{"x":-0.2388916015625,"y":-0.129852294921875},{"x":0.2249755859375,"y":0.102691650390625},{"x":0.05047607421875,"y":-0.03271484375},{"x":0.120361328125,"y":0.003265380859375},{"x":0.24169921875,"y":0.030548095703125},{"x":-0.24652099609375,"y":0.085357666015625},{"x":0.01470947265625,"y":-0.053466796875},{"x":-0.08038330078125,"y":0.151885986328125},{"x":0.5992431640625,"y":0.169403076171875},{"x":0.0723876953125,"y":0.19134521484375},{"x":0.015655517578125,"y":0.26458740234375},{"x":-0.022613525390625,"y":0.10223388671875},{"x":0.15032958984375,"y":0.2698974609375},{"x":0.1171875,"y":0.41949462890625},{"x":-6.103515625E-5,"y":0.450927734375},{"x":-0.04730224609375,"y":0.17132568359375},{"x":0.3829345703125,"y":0.12530517578125},{"x":0.38232421875,"y":-0.0943603515625},{"x":0.314208984375,"y":0.17047119140625},{"x":-0.14166259765625,"y":0.290771484375},{"x":0.05291748046875,"y":0.0103759765625},{"x":-0.18414306640625,"y":-0.113525390625},{"x":-0.01202392578125,"y":-0.14166259765625},{"x":0.197052001953125,"y":0.05908203125},{"x":0.2564697265625,"y":0.0032958984375},{"x":-0.14764404296875,"y":0.00128173828125},{"x":0.088775634765625,"y":0.51934814453125},{"x":0.0614013671875,"y":-0.0111083984375},{"x":-0.037841796875,"y":-0.16278076171875},{"x":-0.25653076171875,"y":0.0211181640625}],"optimisedCameraToObject":{"translation":{"x":0.030663983572605177,"y":0.09924212957492183,"z":0.6759971359780811},"rotation":{"quaternion":{"W":0.9950065596447104,"X":0.05085124118088196,"Y":-0.08407436012820498,"Z":0.017538514857137304}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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":331.2314758300781,"y":419.66583251953125},{"x":357.44915771484375,"y":419.03802490234375},{"x":382.97711181640625,"y":418.446044921875},{"x":408.5722961425781,"y":417.8908996582031},{"x":433.7213134765625,"y":417.1686096191406},{"x":458.3932189941406,"y":416.58123779296875},{"x":482.699951171875,"y":416.211181640625},{"x":331.2535705566406,"y":445.0315246582031},{"x":357.1666259765625,"y":444.2899475097656},{"x":382.68768310546875,"y":443.8746337890625},{"x":408.2138366699219,"y":443.0794677734375},{"x":433.305908203125,"y":442.2578430175781},{"x":458.0511169433594,"y":441.69610595703125},{"x":482.2638854980469,"y":440.8596496582031},{"x":330.9165344238281,"y":470.82818603515625},{"x":357.001953125,"y":469.8637390136719},{"x":382.3955078125,"y":468.73876953125},{"x":407.6886901855469,"y":467.8902587890625},{"x":432.600341796875,"y":467.098876953125},{"x":457.3919982910156,"y":466.1658630371094},{"x":481.945068359375,"y":465.5999450683594},{"x":330.75653076171875,"y":496.0782470703125},{"x":356.6919250488281,"y":495.0561828613281},{"x":381.9559326171875,"y":493.8338928222656},{"x":407.1277160644531,"y":493.00262451171875},{"x":432.05670166015625,"y":492.1134033203125},{"x":456.91552734375,"y":491.15362548828125},{"x":480.8920593261719,"y":490.1383361816406},{"x":330.5964660644531,"y":520.7067260742188},{"x":356.08636474609375,"y":519.8082275390625},{"x":381.7460632324219,"y":518.437255859375},{"x":406.74658203125,"y":517.2041625976562},{"x":431.4792785644531,"y":516.4271850585938},{"x":456.0859069824219,"y":515.18310546875},{"x":480.34814453125,"y":514.2687377929688},{"x":330.1820068359375,"y":545.9888305664062},{"x":355.9835205078125,"y":544.7557983398438},{"x":381.1116943359375,"y":543.740234375},{"x":406.239013671875,"y":542.09375},{"x":431.1082763671875,"y":541.139892578125},{"x":455.7934875488281,"y":539.9381103515625},{"x":480.0440979003906,"y":538.8885498046875},{"x":330.0758361816406,"y":570.7327270507812},{"x":355.3753967285156,"y":569.1998291015625},{"x":380.9862060546875,"y":568.2113037109375},{"x":405.8823547363281,"y":566.947021484375},{"x":430.70703125,"y":565.4312133789062},{"x":455.37213134765625,"y":564.1724853515625},{"x":479.3182373046875,"y":562.9898071289062}],"reprojectionErrors":[{"x":0.15289306640625,"y":-0.160919189453125},{"x":-0.0601806640625,"y":-0.075469970703125},{"x":0.125518798828125,"y":-0.029754638671875},{"x":-0.046661376953125,"y":-0.02459716796875},{"x":-0.062835693359375,"y":0.1441650390625},{"x":0.10845947265625,"y":0.174560546875},{"x":0.35589599609375,"y":-0.015625},{"x":-0.074462890625,"y":0.097412109375},{"x":-0.058563232421875,"y":0.157135009765625},{"x":0.06005859375,"y":-0.113250732421875},{"x":-0.1153564453125,"y":-0.00738525390625},{"x":-0.145172119140625,"y":0.1214599609375},{"x":-0.11614990234375,"y":-0.01287841796875},{"x":0.157958984375,"y":0.1243896484375},{"x":0.057861328125,"y":-0.23089599609375},{"x":-0.174285888671875,"y":-0.08612060546875},{"x":-0.00213623046875,"y":0.21539306640625},{"x":-0.016876220703125,"y":0.2369384765625},{"x":0.063079833984375,"y":0.197967529296875},{"x":-0.0233154296875,"y":0.297454833984375},{"x":-0.156890869140625,"y":0.02691650390625},{"x":0.013641357421875,"y":-0.16827392578125},{"x":-0.1441650390625,"y":-0.102020263671875},{"x":0.083526611328125,"y":0.1607666015625},{"x":0.11785888671875,"y":0.029022216796875},{"x":0.109832763671875,"y":-0.048004150390625},{"x":-0.11273193359375,"y":-0.057525634765625},{"x":0.262847900390625,"y":-0.014373779296875},{"x":-0.02996826171875,"y":0.36029052734375},{"x":0.1820068359375,"y":0.1685791015625},{"x":-0.05999755859375,"y":0.44561767578125},{"x":0.073272705078125,"y":0.58135986328125},{"x":0.190826416015625,"y":0.2578125},{"x":0.15142822265625,"y":0.3984375},{"x":0.17388916015625,"y":0.20660400390625},{"x":0.18133544921875,"y":0.0797119140625},{"x":0.0059814453125,"y":0.0897216796875},{"x":0.22149658203125,"y":-0.12139892578125},{"x":0.155609130859375,"y":0.2950439453125},{"x":0.06591796875,"y":0.0157470703125},{"x":-0.12115478515625,"y":-0.01849365234375},{"x":-0.154510498046875,"y":-0.20751953125},{"x":0.08489990234375,"y":0.18182373046875},{"x":0.335784912109375,"y":0.36053466796875},{"x":-0.00537109375,"y":-0.0086669921875},{"x":0.087554931640625,"y":-0.10552978515625},{"x":-0.02825927734375,"y":0.046142578125},{"x":-0.264312744140625,"y":-0.06207275390625},{"x":-0.06060791015625,"y":-0.248779296875}],"optimisedCameraToObject":{"translation":{"x":-0.08510351053733864,"y":0.08638864545568846,"z":0.657007128678282},"rotation":{"quaternion":{"W":0.9964491993428661,"X":0.03979958203965251,"Y":-0.07405138753240255,"Z":0.004623678509147961}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/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.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":79.41705322265625,"y":412.6457824707031},{"x":108.00381469726562,"y":411.3244323730469},{"x":136.05938720703125,"y":410.4716796875},{"x":164.1924285888672,"y":409.08343505859375},{"x":191.88783264160156,"y":408.0768737792969},{"x":219.79296875,"y":406.983154296875},{"x":245.4607391357422,"y":405.9814758300781},{"x":80.18347930908203,"y":439.5212707519531},{"x":108.6060562133789,"y":438.123291015625},{"x":136.9456787109375,"y":437.0024108886719},{"x":164.80026245117188,"y":435.5784912109375},{"x":192.12167358398438,"y":434.45269775390625},{"x":219.65176391601562,"y":432.85791015625},{"x":245.95993041992188,"y":431.7634582519531},{"x":80.98406219482422,"y":466.06695556640625},{"x":109.29608154296875,"y":464.751220703125},{"x":137.56219482421875,"y":462.9157409667969},{"x":165.4318389892578,"y":461.8831787109375},{"x":192.87132263183594,"y":460.0674743652344},{"x":219.9458465576172,"y":458.8800354003906},{"x":246.24179077148438,"y":457.25238037109375},{"x":81.7502670288086,"y":492.8155517578125},{"x":110.0806884765625,"y":490.96685791015625},{"x":138.06175231933594,"y":489.39642333984375},{"x":165.8417205810547,"y":488.01123046875},{"x":193.27330017089844,"y":486.28662109375},{"x":220.19271850585938,"y":484.9385070800781},{"x":246.88641357421875,"y":483.18231201171875},{"x":82.42625427246094,"y":518.9642333984375},{"x":110.8089599609375,"y":517.2395629882812},{"x":138.79881286621094,"y":515.4427490234375},{"x":166.10366821289062,"y":513.7586669921875},{"x":193.71697998046875,"y":511.91571044921875},{"x":220.83261108398438,"y":510.2893371582031},{"x":247.11602783203125,"y":508.40679931640625},{"x":83.30671691894531,"y":545.2686767578125},{"x":111.49689483642578,"y":543.816650390625},{"x":139.21246337890625,"y":541.5189208984375},{"x":166.98338317871094,"y":539.8679809570312},{"x":194.01492309570312,"y":537.9791259765625},{"x":221.09169006347656,"y":536.0531616210938},{"x":247.81048583984375,"y":534.2291259765625},{"x":84.15645599365234,"y":571.4194946289062},{"x":112.11708068847656,"y":569.4663696289062},{"x":139.80406188964844,"y":567.9172973632812},{"x":167.52000427246094,"y":565.4815063476562},{"x":194.43228149414062,"y":563.7354736328125},{"x":221.26251220703125,"y":561.8145751953125},{"x":247.91995239257812,"y":559.7775268554688}],"reprojectionErrors":[{"x":-0.02587127685546875,"y":-0.229095458984375},{"x":0.01496124267578125,"y":0.031951904296875},{"x":0.21697998046875,"y":-0.170013427734375},{"x":-0.026214599609375,"y":0.16925048828125},{"x":-0.1971435546875,"y":0.132568359375},{"x":-0.940765380859375,"y":0.188934326171875},{"x":0.1924896240234375,"y":0.15911865234375},{"x":-0.059173583984375,"y":-0.248931884765625},{"x":0.08567047119140625,"y":-0.087554931640625},{"x":-0.0550689697265625,"y":-0.1968994140625},{"x":-0.077056884765625,"y":0.00323486328125},{"x":0.0701751708984375,"y":-0.088226318359375},{"x":-0.35284423828125,"y":0.2958984375},{"x":0.0869598388671875,"y":0.1864013671875},{"x":-0.125885009765625,"y":-0.046875},{"x":0.06905364990234375,"y":-0.142547607421875},{"x":-0.0571746826171875,"y":0.28857421875},{"x":-0.151763916015625,"y":-0.0760498046875},{"x":-0.1787261962890625,"y":0.3497314453125},{"x":-0.200897216796875,"y":0.15460205078125},{"x":0.197784423828125,"y":0.40716552734375},{"x":-0.15750885009765625,"y":-0.15643310546875},{"x":-0.0417327880859375,"y":0.107452392578125},{"x":0.0578155517578125,"y":0.100799560546875},{"x":-0.00494384765625,"y":-0.08319091796875},{"x":-0.0803985595703125,"y":0.0802001953125},{"x":-0.0024566650390625,"y":-0.124786376953125},{"x":-0.0551300048828125,"y":0.086517333984375},{"x":-0.09824371337890625,"y":0.224365234375},{"x":-0.09580230712890625,"y":0.1922607421875},{"x":-0.0646209716796875,"y":0.24066162109375},{"x":0.2896270751953125,"y":0.18499755859375},{"x":-0.02423095703125,"y":0.29681396484375},{"x":-0.19775390625,"y":0.200927734375},{"x":0.1059722900390625,"y":0.370147705078125},{"x":-0.242828369140625,"y":0.3389892578125},{"x":-0.10919189453125,"y":-0.13629150390625},{"x":0.1364288330078125,"y":0.24322509765625},{"x":-0.0337677001953125,"y":-0.01483154296875},{"x":0.17718505859375,"y":-0.02557373046875},{"x":-0.01300048828125,"y":0.01031494140625},{"x":-0.1987762451171875,"y":-0.0460205078125},{"x":-0.35611724853515625,"y":0.49609375},{"x":-0.05454254150390625,"y":0.35284423828125},{"x":0.1595458984375,"y":-0.18475341796875},{"x":-0.0143280029296875,"y":0.17425537109375},{"x":0.258697509765625,"y":-0.14642333984375},{"x":0.259246826171875,"y":-0.281982421875},{"x":0.0804443359375,"y":-0.291015625}],"optimisedCameraToObject":{"translation":{"x":-0.3193690600708015,"y":0.07589749250509525,"z":0.6321032365491306},"rotation":{"quaternion":{"W":0.9959781663685361,"X":0.024649193271525288,"Y":-0.08603038983297161,"Z":-0.004322200066939342}}},"includeObservationInCalibration":true,"snapshotName":"img21.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/54fce204-aaca-41a4-a17f-a3c4a1e53d47/imgs/800x600/img21.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[682.7516943236313,0.0,394.5499847505025,0.0,683.1022199586625,306.9550449132658,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04877412168568248,-0.08583346617497362,3.3239861329365287E-4,-1.0087681700342245E-4,0.0373919549435751,-0.001607828934539453,0.003334945484145628,-0.0015418411274107935]},"calobjectWarp":[-1.7967371837738374E-4,-1.0056455082665219E-4],"observations":[{"locationInObjectSpace":[{"x":0.09083039313554764,"y":0.0,"z":-1.7600689898245037E-4},{"x":0.10596879571676254,"y":0.0,"z":-1.796737196855247E-4},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.18166080117225647,"y":0.0,"z":-8.800344949122518E-5},{"x":0.19679918885231018,"y":0.0,"z":-4.766857091453858E-5},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.16652239859104156,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.18166080117225647,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.19679918885231018,"y":0.015138399787247181,"z":-8.387180423596874E-5},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083039313554764,"y":0.03027680143713951,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.03027680143713951,"z":-2.293677971465513E-4},{"x":0.15138399600982666,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.16652239859104156,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.18166080117225647,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.19679918885231018,"y":0.03027680143713951,"z":-1.1202988389413804E-4},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.04541520029306412,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.04541520029306412,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.04541520029306412,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.060553599148988724,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.18166080117225647,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.19679918885231018,"y":0.07569199800491333,"z":-1.482331135775894E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.09083039313554764,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.10596879571676254,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.07569199800491333,"y":0.12110719084739685,"z":-2.293677971465513E-4},{"x":0.09083039313554764,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.10596879571676254,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.15138399600982666,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.16652239859104156,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.18166080117225647,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.19679918885231018,"y":0.12110719084739685,"z":-1.1202989844605327E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.07569199800491333,"y":0.13624559342861176,"z":-2.0120972476433963E-4},{"x":0.09083039313554764,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.10596879571676254,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.13624559342861176,"y":0.13624559342861176,"z":-2.0120973931625485E-4},{"x":0.15138399600982666,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.16652239859104156,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.18166080117225647,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":458.0697937011719,"y":188.22500610351562},{"x":480.5665588378906,"y":185.16612243652344},{"x":503.3921813964844,"y":182.11317443847656},{"x":572.5305786132812,"y":172.48153686523438},{"x":596.0140380859375,"y":169.4591522216797},{"x":619.4346923828125,"y":166.13946533203125},{"x":437.92462158203125,"y":211.02813720703125},{"x":460.43060302734375,"y":207.95982360839844},{"x":483.4458923339844,"y":205.10855102539062},{"x":506.5277099609375,"y":201.68521118164062},{"x":576.2572021484375,"y":192.322265625},{"x":600.1422119140625,"y":189.33209228515625},{"x":623.8291625976562,"y":186.02777099609375},{"x":372.8437805175781,"y":240.04116821289062},{"x":394.9493408203125,"y":236.83200073242188},{"x":417.27783203125,"y":233.9010467529297},{"x":440.1217346191406,"y":230.94065856933594},{"x":463.04608154296875,"y":228.01536560058594},{"x":486.0346374511719,"y":224.79617309570312},{"x":508.018310546875,"y":222.53338623046875},{"x":532.98681640625,"y":218.9586639404297},{"x":556.2896728515625,"y":215.91390991210938},{"x":580.267578125,"y":212.73960876464844},{"x":604.584716796875,"y":209.42185974121094},{"x":628.7138061523438,"y":206.427001953125},{"x":351.20623779296875,"y":263.21295166015625},{"x":419.5162353515625,"y":254.6029815673828},{"x":442.317626953125,"y":251.33287048339844},{"x":512.7411499023438,"y":242.56640625},{"x":536.2963256835938,"y":239.54922485351562},{"x":560.367431640625,"y":236.51229858398438},{"x":584.680908203125,"y":233.850341796875},{"x":608.9337158203125,"y":230.45712280273438},{"x":633.218017578125,"y":227.4756317138672},{"x":329.9703674316406,"y":286.9299011230469},{"x":352.12774658203125,"y":284.38458251953125},{"x":421.4462890625,"y":275.7034912109375},{"x":444.9581298828125,"y":272.6667175292969},{"x":540.0498657226562,"y":260.9295959472656},{"x":564.3477172851562,"y":257.67987060546875},{"x":588.88720703125,"y":254.80421447753906},{"x":613.5059204101562,"y":251.833251953125},{"x":638.2518310546875,"y":248.75604248046875},{"x":330.9082946777344,"y":308.326171875},{"x":353.8084411621094,"y":305.8206787109375},{"x":376.80902099609375,"y":302.98028564453125},{"x":400.1733093261719,"y":299.97906494140625},{"x":423.5917053222656,"y":297.1226806640625},{"x":447.1124267578125,"y":294.26715087890625},{"x":470.99090576171875,"y":291.3049011230469},{"x":568.1796264648438,"y":279.60589599609375},{"x":593.0707397460938,"y":276.7436828613281},{"x":618.2527465820312,"y":273.681884765625},{"x":643.2560424804688,"y":270.7465515136719},{"x":331.91082763671875,"y":330.7736511230469},{"x":401.9180908203125,"y":322.14105224609375},{"x":425.7900390625,"y":319.3580627441406},{"x":449.63641357421875,"y":316.5155944824219},{"x":473.766357421875,"y":313.9094543457031},{"x":572.5194091796875,"y":302.09490966796875},{"x":598.0172729492188,"y":299.1690368652344},{"x":623.1375122070312,"y":296.1230163574219},{"x":648.7464599609375,"y":293.24908447265625},{"x":332.8150634765625,"y":353.03717041015625},{"x":404.0612487792969,"y":344.95526123046875},{"x":427.9584045410156,"y":342.008544921875},{"x":452.18505859375,"y":339.0807800292969},{"x":476.7786865234375,"y":336.4750061035156},{"x":577.1005249023438,"y":325.04083251953125},{"x":602.4990234375,"y":322.24346923828125},{"x":628.1435546875,"y":319.3319396972656},{"x":654.0064697265625,"y":316.44598388671875},{"x":333.9119567871094,"y":376.5509033203125},{"x":357.63348388671875,"y":373.6996154785156},{"x":381.7432861328125,"y":370.7982482910156},{"x":406.03265380859375,"y":368.04193115234375},{"x":430.4234619140625,"y":365.1866149902344},{"x":455.0362548828125,"y":362.68603515625},{"x":479.81640625,"y":359.9466857910156},{"x":504.9034118652344,"y":357.2443542480469},{"x":581.4649658203125,"y":348.795654296875},{"x":607.29931640625,"y":346.03082275390625},{"x":633.5387573242188,"y":343.2580261230469},{"x":659.6691284179688,"y":340.3973693847656},{"x":334.7090759277344,"y":400.03662109375},{"x":358.9177551269531,"y":397.7298278808594},{"x":383.200927734375,"y":394.9403076171875},{"x":407.97686767578125,"y":392.2448425292969},{"x":432.908203125,"y":389.49456787109375},{"x":457.9516906738281,"y":386.73577880859375},{"x":482.90899658203125,"y":383.8548583984375},{"x":508.2190856933594,"y":381.5206604003906},{"x":534.306396484375,"y":378.81768798828125},{"x":559.9483642578125,"y":376.14654541015625},{"x":586.1402587890625,"y":373.2123107910156},{"x":612.1219482421875,"y":370.6105041503906},{"x":638.601806640625,"y":367.8280029296875},{"x":665.3864135742188,"y":364.96502685546875}],"reprojectionErrors":[{"x":0.19384765625,"y":-0.2371826171875},{"x":0.347930908203125,"y":-0.2126312255859375},{"x":0.146240234375,"y":-0.4201812744140625},{"x":-0.160400390625,"y":-0.1642608642578125},{"x":-0.1015625,"y":-0.0093994140625},{"x":-0.417205810546875,"y":-0.2486572265625},{"x":1.672943115234375,"y":-0.7783660888671875},{"x":0.13372802734375,"y":-0.2636566162109375},{"x":0.4193115234375,"y":-0.2943115234375},{"x":0.18951416015625,"y":-0.2108612060546875},{"x":0.0120849609375,"y":-0.029815673828125},{"x":0.03240966796875,"y":-0.2237548828125},{"x":0.327667236328125,"y":0.08056640625},{"x":0.18756103515625,"y":-0.1625213623046875},{"x":-0.0545654296875,"y":-0.5604095458984375},{"x":-0.07147216796875,"y":-0.2427978515625},{"x":0.04510498046875,"y":-0.3526763916015625},{"x":-0.34674072265625,"y":0.0850830078125},{"x":0.244384765625,"y":-0.236572265625},{"x":0.03985595703125,"y":-0.14459228515625},{"x":0.216552734375,"y":-0.287689208984375},{"x":0.1534423828125,"y":-0.0479736328125},{"x":0.01708984375,"y":-0.1983795166015625},{"x":-0.02960205078125,"y":-0.26953125},{"x":-0.39532470703125,"y":0.160430908203125},{"x":-0.02392578125,"y":-0.022857666015625},{"x":0.10516357421875,"y":-0.04205322265625},{"x":0.37176513671875,"y":-0.118988037109375},{"x":0.22430419921875,"y":-0.246063232421875},{"x":-0.04058837890625,"y":-0.189910888671875},{"x":0.04742431640625,"y":-0.276611328125},{"x":-0.4825439453125,"y":-0.251983642578125},{"x":0.0721435546875,"y":-0.022491455078125},{"x":0.0650634765625,"y":-0.073211669921875},{"x":0.256866455078125,"y":-0.080841064453125},{"x":-0.21435546875,"y":-0.181488037109375},{"x":-0.06292724609375,"y":-0.101470947265625},{"x":0.11383056640625,"y":0.0784912109375},{"x":0.255645751953125,"y":0.201141357421875},{"x":0.209259033203125,"y":-0.014862060546875},{"x":-0.1204833984375,"y":-0.03582763671875},{"x":-0.06640625,"y":-0.144439697265625},{"x":-0.0750732421875,"y":-0.1558837890625},{"x":-0.11810302734375,"y":-0.209869384765625},{"x":-0.5711669921875,"y":-0.183013916015625},{"x":-0.311614990234375,"y":-0.02099609375},{"x":-0.259979248046875,"y":0.17437744140625},{"x":-0.20672607421875,"y":0.2078857421875},{"x":-0.0728759765625,"y":0.323577880859375},{"x":-0.09783935546875,"y":-0.08001708984375},{"x":-0.1104736328125,"y":-0.1741943359375},{"x":-0.33966064453125,"y":-0.277679443359375},{"x":-0.2705078125,"y":-0.310577392578125},{"x":-0.36895751953125,"y":0.18792724609375},{"x":-0.152130126953125,"y":0.02081298828125},{"x":-0.215728759765625,"y":0.08404541015625},{"x":-0.20355224609375,"y":0.138671875},{"x":0.08355712890625,"y":0.2982177734375},{"x":-0.2647705078125,"y":-0.117767333984375},{"x":-0.04522705078125,"y":-0.32415771484375},{"x":-0.1298828125,"y":-0.36737060546875},{"x":-0.32452392578125,"y":-0.347686767578125}],"optimisedCameraToObject":{"translation":{"x":-0.046819463306286405,"y":-0.06897090555053786,"z":0.46842308759731155},"rotation":{"quaternion":{"W":0.9791219412951526,"X":-0.1876859750074441,"Y":0.06066460115427716,"Z":-0.049132525140778316}}},"cornersUsed":[false,false,false,false,false,false,true,true,true,false,false,true,true,true,false,false,false,false,false,true,true,true,true,false,false,true,true,true,false,false,true,true,true,true,true,true,false,true,true,true,true,true,false,true,false,false,true,true,false,false,true,true,true,true,true,true,true,true,false,false,true,true,false,false,false,true,true,true,true,true,true,true,true,true,true,true,true,false,false,false,true,true,true,true,true,false,false,true,true,true,true,false,false,false,true,true,true,true,true,false,false,true,true,true,true,false,false,false,true,true,true,true,true,true,true,true,true,true,true,true,false,false,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.015138402581214905,"y":0.0,"z":-4.766854544868693E-5},{"x":0.10596880316734314,"y":0.0,"z":-1.796737196855247E-4},{"x":0.0,"y":0.015138400718569756,"z":-3.6203240597387776E-5},{"x":0.015138402581214905,"y":0.015138400718569756,"z":-8.38717824080959E-5},{"x":0.0,"y":0.030276799574494362,"z":-6.436130934162065E-5},{"x":0.015138402581214905,"y":0.030276799574494362,"z":-1.1202985479030758E-4},{"x":0.030276797711849213,"y":0.030276799574494362,"z":-1.5236476610880345E-4},{"x":0.13624559342861176,"y":0.030276799574494362,"z":-2.293677971465513E-4},{"x":0.015138402581214905,"y":0.04541520029306412,"z":-1.321427698712796E-4},{"x":0.030276797711849213,"y":0.04541520029306412,"z":-1.7247766663786024E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553595423698425,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.12110720574855804,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.030276797711849213,"y":0.06055360287427902,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.06055360287427902,"z":-2.1754672343377024E-4},{"x":0.060553595423698425,"y":0.06055360287427902,"z":-2.4321438104379922E-4},{"x":0.07569199800491333,"y":0.06055360287427902,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.06055360287427902,"z":-2.7254887390881777E-4},{"x":0.10596880316734314,"y":0.06055360287427902,"z":-2.762156946118921E-4},{"x":0.12110720574855804,"y":0.06055360287427902,"z":-2.7254887390881777E-4},{"x":0.030276797711849213,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553595423698425,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083040058612823,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596880316734314,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110720574855804,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.015138402581214905,"y":0.09083040058612823,"z":-1.4421051309909672E-4},{"x":0.030276797711849213,"y":0.09083040058612823,"z":-1.8454540986567736E-4},{"x":0.04541520029306412,"y":0.09083040058612823,"z":-2.1754672343377024E-4},{"x":0.060553595423698425,"y":0.09083040058612823,"z":-2.4321438104379922E-4},{"x":0.07569199800491333,"y":0.09083040058612823,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.09083040058612823,"z":-2.7254887390881777E-4},{"x":0.10596880316734314,"y":0.09083040058612823,"z":-2.762156946118921E-4},{"x":0.12110720574855804,"y":0.09083040058612823,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.09083040058612823,"z":-2.615484409034252E-4},{"x":0.015138402581214905,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.030276797711849213,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553595423698425,"y":0.10596879571676254,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083040058612823,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596880316734314,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110720574855804,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.015138402581214905,"y":0.12110719829797745,"z":-1.120298620662652E-4},{"x":0.030276797711849213,"y":0.12110719829797745,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.12110719829797745,"z":-1.853660651249811E-4},{"x":0.060553595423698425,"y":0.12110719829797745,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.12110719829797745,"z":-2.2936778259463608E-4},{"x":0.09083040058612823,"y":0.12110719829797745,"z":-2.4036823015194386E-4},{"x":0.10596880316734314,"y":0.12110719829797745,"z":-2.4403503630310297E-4},{"x":0.12110720574855804,"y":0.12110719829797745,"z":-2.4036821560002863E-4},{"x":0.13624559342861176,"y":0.12110719829797745,"z":-2.293677971465513E-4}],"locationInImageSpace":[{"x":365.1298522949219,"y":40.00737762451172},{"x":505.7548522949219,"y":27.945817947387695},{"x":342.236572265625,"y":60.297386169433594},{"x":365.5314025878906,"y":58.40753173828125},{"x":342.1869201660156,"y":79.59735870361328},{"x":365.9314270019531,"y":77.94554138183594},{"x":389.15386962890625,"y":75.91256713867188},{"x":558.9563598632812,"y":61.62605285644531},{"x":365.9764709472656,"y":97.63445281982422},{"x":390.01129150390625,"y":95.81075286865234},{"x":414.0498046875,"y":93.74298858642578},{"x":437.9288330078125,"y":91.3733901977539},{"x":462.9100646972656,"y":89.7154312133789},{"x":536.6268310546875,"y":83.50675201416016},{"x":390.4664001464844,"y":115.62908935546875},{"x":414.9228210449219,"y":113.85478210449219},{"x":439.3782043457031,"y":111.93830871582031},{"x":464.13531494140625,"y":109.82633209228516},{"x":489.0034484863281,"y":108.08576202392578},{"x":513.7706298828125,"y":105.97297668457031},{"x":539.2047119140625,"y":103.74186706542969},{"x":391.13568115234375,"y":136.31309509277344},{"x":415.9981689453125,"y":134.52891540527344},{"x":440.5655517578125,"y":132.7245330810547},{"x":465.656494140625,"y":130.71768188476562},{"x":490.76824951171875,"y":128.7725067138672},{"x":516.1844482421875,"y":126.81050109863281},{"x":541.5548095703125,"y":124.80411529541016},{"x":567.28271484375,"y":122.71430969238281},{"x":366.9726257324219,"y":159.21934509277344},{"x":391.7458801269531,"y":157.55397033691406},{"x":416.8453063964844,"y":155.7328643798828},{"x":441.95166015625,"y":154.0059814453125},{"x":467.2168273925781,"y":151.9442596435547},{"x":492.41741943359375,"y":150.18418884277344},{"x":518.3015747070312,"y":148.060791015625},{"x":544.1095581054688,"y":146.153564453125},{"x":570.0598754882812,"y":144.05450439453125},{"x":367.63397216796875,"y":181.1631622314453},{"x":392.09954833984375,"y":179.27816772460938},{"x":417.6607971191406,"y":177.46572875976562},{"x":443.0783386230469,"y":175.76634216308594},{"x":468.8329162597656,"y":173.81394958496094},{"x":494.67840576171875,"y":172.06008911132812},{"x":520.6168823242188,"y":170.0739288330078},{"x":546.954833984375,"y":168.13331604003906},{"x":573.216552734375,"y":166.08169555664062},{"x":367.74688720703125,"y":203.26966857910156},{"x":392.8927917480469,"y":201.5155487060547},{"x":418.55474853515625,"y":200.00404357910156},{"x":444.1979675292969,"y":197.8770751953125},{"x":470.4451904296875,"y":196.20135498046875},{"x":496.6421813964844,"y":194.18995666503906},{"x":522.8888549804688,"y":192.51388549804688},{"x":549.6306762695312,"y":190.8389129638672},{"x":576.4472045898438,"y":188.91021728515625}],"reprojectionErrors":[{"x":0.1705322265625,"y":-0.37511444091796875},{"x":0.07183837890625,"y":-0.3860015869140625},{"x":-0.037628173828125,"y":-0.4411773681640625},{"x":0.0445556640625,"y":-0.2835540771484375},{"x":-0.033203125,"y":-0.0136871337890625},{"x":-0.42303466796875,"y":0.0659942626953125},{"x":9.46044921875E-4,"y":0.01312255859375},{"x":-0.146728515625,"y":-0.162567138671875}],"optimisedCameraToObject":{"translation":{"x":-0.03414136860382011,"y":-0.17318560140350425,"z":0.4466612275745274},"rotation":{"quaternion":{"W":0.9823273132191163,"X":-0.18077771325781525,"Y":0.04378225872242183,"Z":-0.020870599276262846}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,true,false,false,false,false,false,false,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,true,false,false,false,false,false,true,true,true,true,true,false,false,true,false,false,false,false,false,false,false,true,true,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true],"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.03027680143713951,"y":0.0,"z":-8.80034567671828E-5},{"x":0.015138399787247181,"y":0.015138399787247181,"z":-8.387177513213828E-5},{"x":0.03027680143713951,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138399787247181,"y":0.03027680143713951,"z":-1.1202985479030758E-4},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083039313554764,"y":0.03027680143713951,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083039313554764,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4}],"locationInImageSpace":[{"x":558.137939453125,"y":22.877365112304688},{"x":535.2265625,"y":47.393516540527344},{"x":561.8321533203125,"y":43.528892517089844},{"x":643.2020263671875,"y":32.16866683959961},{"x":670.8301391601562,"y":28.33759307861328},{"x":698.30908203125,"y":24.82256507873535},{"x":725.9634399414062,"y":20.887453079223633},{"x":512.1043090820312,"y":72.14006805419922},{"x":539.0265502929688,"y":68.36539459228516},{"x":565.7794799804688,"y":64.77849578857422},{"x":593.160400390625,"y":60.63166427612305},{"x":620.4461669921875,"y":57.21889114379883},{"x":648.34228515625,"y":53.317344665527344},{"x":675.9873657226562,"y":49.7095832824707},{"x":704.5243530273438,"y":45.58319854736328},{"x":732.2513427734375,"y":42.19216537475586},{"x":515.3950805664062,"y":93.58560943603516},{"x":542.4566040039062,"y":90.12291717529297},{"x":570.1375122070312,"y":86.23074340820312},{"x":597.5751342773438,"y":82.50093078613281},{"x":625.4989624023438,"y":78.82056427001953},{"x":653.5914306640625,"y":75.08053588867188},{"x":681.833740234375,"y":71.49560546875},{"x":710.317626953125,"y":67.83444213867188},{"x":738.996337890625,"y":63.70845031738281},{"x":518.7913208007812,"y":115.9002685546875},{"x":546.2973022460938,"y":112.19408416748047},{"x":574.07958984375,"y":108.71598052978516},{"x":602.2593383789062,"y":104.91374206542969},{"x":630.2532958984375,"y":101.1832275390625},{"x":659.1666870117188,"y":97.30784606933594},{"x":687.6517333984375,"y":93.48084259033203},{"x":716.7442626953125,"y":89.9105224609375},{"x":745.6995239257812,"y":86.23795318603516},{"x":522.2706909179688,"y":138.7532196044922},{"x":550.0237426757812,"y":135.21681213378906},{"x":578.5408325195312,"y":131.6767578125},{"x":606.8974609375,"y":127.9819107055664},{"x":635.6918334960938,"y":124.1731185913086},{"x":664.8388061523438,"y":120.60562896728516},{"x":693.7510375976562,"y":116.77987670898438},{"x":723.348876953125,"y":112.92757415771484},{"x":752.8070678710938,"y":109.29080963134766},{"x":525.7637329101562,"y":162.35548400878906},{"x":553.9654541015625,"y":158.96978759765625},{"x":582.7544555664062,"y":155.1926727294922},{"x":611.7468872070312,"y":151.76394653320312},{"x":640.9434204101562,"y":148.0216827392578},{"x":529.2388305664062,"y":186.54261779785156},{"x":558.174560546875,"y":183.07061767578125},{"x":587.2980346679688,"y":179.49420166015625},{"x":616.7968139648438,"y":176.07278442382812},{"x":646.5482788085938,"y":172.44383239746094},{"x":533.3035278320312,"y":211.81234741210938},{"x":562.2549438476562,"y":208.1697998046875},{"x":592.05517578125,"y":204.852783203125},{"x":621.8523559570312,"y":201.28341674804688},{"x":651.4462280273438,"y":197.68911743164062},{"x":537.1612548828125,"y":236.93255615234375},{"x":566.537109375,"y":233.76502990722656},{"x":596.9017944335938,"y":230.60350036621094},{"x":627.0811157226562,"y":227.2668914794922}],"reprojectionErrors":[{"x":0.20855712890625,"y":-0.05670928955078125},{"x":0.4066162109375,"y":-0.6713180541992188},{"x":0.04632568359375,"y":-0.07283782958984375},{"x":0.05267333984375,"y":-0.12030792236328125},{"x":-0.01202392578125,"y":-0.1965179443359375},{"x":-0.01104736328125,"y":-0.23615264892578125},{"x":0.0758056640625,"y":-0.45406341552734375},{"x":-0.05133056640625,"y":-0.2147216796875},{"x":0.24700927734375,"y":-0.20053863525390625},{"x":-0.1326904296875,"y":-0.06497955322265625},{"x":0.158935546875,"y":-0.00138092041015625},{"x":0.087646484375,"y":-0.21816253662109375},{"x":0.399658203125,"y":-0.35646820068359375},{"x":-0.086181640625,"y":-0.18408203125},{"x":0.16253662109375,"y":-0.2485198974609375},{"x":-0.10882568359375,"y":-0.3328704833984375},{"x":0.31402587890625,"y":-0.194061279296875},{"x":-0.0567626953125,"y":-0.2309722900390625},{"x":0.180419921875,"y":-0.3959808349609375},{"x":0.0816650390625,"y":-0.1934814453125},{"x":0.03271484375,"y":-0.3633880615234375},{"x":0.0345458984375,"y":-0.2438812255859375},{"x":0.0970458984375,"y":-0.1381683349609375},{"x":0.050537109375,"y":-0.161865234375},{"x":0.07550048828125,"y":-0.105377197265625},{"x":0.0880126953125,"y":-0.2226104736328125},{"x":0.65576171875,"y":-0.1378021240234375},{"x":-0.22918701171875,"y":0.335418701171875},{"x":0.22705078125,"y":0.1333465576171875},{"x":-0.029541015625,"y":-0.0995330810546875},{"x":0.17730712890625,"y":-0.1822967529296875}],"optimisedCameraToObject":{"translation":{"x":0.0655934022001534,"y":-0.16249833324622767,"z":0.4017522145924247},"rotation":{"quaternion":{"W":0.9802582683545559,"X":-0.18366359586330966,"Y":0.06089068964443614,"Z":-0.04066613814602245}}},"cornersUsed":[false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,false,false,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,false,false],"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.060553599148988724,"y":0.0,"z":-1.4667242066934705E-4},{"x":0.07569199800491333,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.09083039313554764,"y":0.0,"z":-1.7600689898245037E-4},{"x":0.10596879571676254,"y":0.0,"z":-1.796737196855247E-4},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.13624559342861176,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.15138399600982666,"y":0.0,"z":-1.4667243522126228E-4},{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.18166080117225647,"y":0.0,"z":-8.800344949122518E-5},{"x":0.19679918885231018,"y":0.0,"z":-4.766857091453858E-5},{"x":0.060553599148988724,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.13624559342861176,"y":0.015138399787247181,"z":-2.0120972476433963E-4},{"x":0.15138399600982666,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.16652239859104156,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083039313554764,"y":0.03027680143713951,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.03027680143713951,"z":-2.293677971465513E-4},{"x":0.15138399600982666,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.16652239859104156,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083039313554764,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.04541520029306412,"z":-2.494807122275233E-4},{"x":0.18166080117225647,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.04541520029306412,"z":-1.3214279897511005E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.18166080117225647,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.060553599148988724,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.19679918885231018,"y":0.10596879571676254,"z":-1.3214279897511005E-4},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.07569199800491333,"y":0.12110719084739685,"z":-2.293677971465513E-4},{"x":0.09083039313554764,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.10596879571676254,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.07569199800491333,"y":0.13624559342861176,"z":-2.0120972476433963E-4},{"x":0.09083039313554764,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.10596879571676254,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.13624559342861176,"z":-2.1221015776973218E-4}],"locationInImageSpace":[{"x":528.307373046875,"y":274.7949523925781},{"x":549.9556274414062,"y":272.2611083984375},{"x":571.2125244140625,"y":270.3226623535156},{"x":593.2522583007812,"y":267.8631286621094},{"x":615.77587890625,"y":265.78338623046875},{"x":638.6861572265625,"y":263.22186279296875},{"x":661.2365112304688,"y":261.00897216796875},{"x":684.7418212890625,"y":258.76995849609375},{"x":708.6629638671875,"y":256.068359375},{"x":732.3875122070312,"y":254.05368041992188},{"x":529.7793579101562,"y":293.7116394042969},{"x":551.7725219726562,"y":291.3599548339844},{"x":573.5811767578125,"y":289.10650634765625},{"x":595.7408447265625,"y":286.9660949707031},{"x":618.9957275390625,"y":285.1078796386719},{"x":641.4423217773438,"y":282.46087646484375},{"x":665.0226440429688,"y":280.29571533203125},{"x":689.0665283203125,"y":278.2348937988281},{"x":531.512939453125,"y":312.7163391113281},{"x":553.5891723632812,"y":310.5579833984375},{"x":575.992919921875,"y":308.9488220214844},{"x":598.7822875976562,"y":306.8076477050781},{"x":621.5939331054688,"y":304.2615966796875},{"x":645.1847534179688,"y":302.5587463378906},{"x":668.7240600585938,"y":300.347900390625},{"x":692.9080810546875,"y":298.0234375},{"x":511.16864013671875,"y":334.1908264160156},{"x":533.238525390625,"y":332.3530578613281},{"x":555.7392578125,"y":330.8931884765625},{"x":578.1386108398438,"y":328.6977233886719},{"x":601.4945068359375,"y":326.9735412597656},{"x":624.9711303710938,"y":324.9736633300781},{"x":648.5176391601562,"y":322.94024658203125},{"x":721.86328125,"y":316.6202697753906},{"x":746.8681640625,"y":314.8149719238281},{"x":491.0425109863281,"y":356.19384765625},{"x":512.9415893554688,"y":354.7389831542969},{"x":534.984619140625,"y":352.83148193359375},{"x":557.9813842773438,"y":351.0308837890625},{"x":580.824951171875,"y":349.3463439941406},{"x":604.1525268554688,"y":347.5060729980469},{"x":628.1882934570312,"y":345.848388671875},{"x":726.872314453125,"y":338.0292663574219},{"x":752.0193481445312,"y":336.0814208984375},{"x":447.79327392578125,"y":380.7911682128906},{"x":469.9198913574219,"y":378.6308288574219},{"x":537.0505981445312,"y":373.81201171875},{"x":560.07666015625,"y":372.00189208984375},{"x":583.5030517578125,"y":370.6822509765625},{"x":606.9530029296875,"y":368.61480712890625},{"x":449.2855529785156,"y":401.18994140625},{"x":470.9940490722656,"y":399.8943176269531},{"x":562.3297119140625,"y":394.0592346191406},{"x":585.9244384765625,"y":392.231201171875},{"x":449.5760803222656,"y":422.6255187988281},{"x":471.8785400390625,"y":421.86102294921875},{"x":494.685546875,"y":420.06341552734375},{"x":564.8964233398438,"y":416.0641784667969},{"x":588.8307495117188,"y":414.94482421875},{"x":768.9838256835938,"y":404.9325866699219},{"x":473.3303527832031,"y":444.021728515625},{"x":496.1233215332031,"y":443.0205993652344},{"x":519.8238525390625,"y":441.7005310058594},{"x":543.2627563476562,"y":440.576904296875},{"x":567.4541625976562,"y":439.31622314453125},{"x":591.4789428710938,"y":438.0569763183594},{"x":616.7256469726562,"y":437.00262451171875},{"x":474.2317199707031,"y":467.2280578613281},{"x":497.85101318359375,"y":466.11627197265625},{"x":521.3065795898438,"y":465.0653991699219},{"x":545.2451782226562,"y":464.087646484375},{"x":569.9932250976562,"y":462.9776306152344},{"x":594.881103515625,"y":462.0904846191406},{"x":620.0166625976562,"y":461.0064697265625},{"x":645.225830078125,"y":459.99053955078125}],"reprojectionErrors":[{"x":0.16864013671875,"y":-0.227264404296875},{"x":-0.11627197265625,"y":0.0277099609375},{"x":0.2603759765625,"y":-0.09173583984375},{"x":-0.01116943359375,"y":-0.21124267578125},{"x":-0.38653564453125,"y":0.105224609375},{"x":-0.2479248046875,"y":-0.2923126220703125},{"x":0.25128173828125,"y":-0.411651611328125},{"x":0.0303955078125,"y":-0.1734619140625},{"x":0.2840576171875,"y":-0.0570068359375},{"x":0.481689453125,"y":-0.077484130859375},{"x":0.23486328125,"y":-0.128387451171875},{"x":0.243408203125,"y":0.016632080078125},{"x":0.22271728515625,"y":-0.4102783203125},{"x":0.1197509765625,"y":-0.328277587890625},{"x":0.30322265625,"y":0.13507080078125},{"x":0.02154541015625,"y":-0.268646240234375},{"x":0.1109619140625,"y":-0.188690185546875},{"x":-0.119140625,"y":-0.01983642578125},{"x":0.14862060546875,"y":-0.278411865234375},{"x":-0.2000732421875,"y":-0.089691162109375},{"x":-0.1864013671875,"y":-0.37689208984375},{"x":-0.260772705078125,"y":0.141693115234375},{"x":-0.03851318359375,"y":-0.155731201171875},{"x":0.3446044921875,"y":-0.02069091796875},{"x":0.08428955078125,"y":-0.013092041015625},{"x":0.29290771484375,"y":-0.1424560546875},{"x":-0.05780029296875,"y":0.060638427734375},{"x":0.14697265625,"y":-0.021087646484375},{"x":0.197265625,"y":0.1170654296875},{"x":0.17230224609375,"y":-0.25506591796875},{"x":0.45477294921875,"y":0.1004638671875},{"x":-0.640167236328125,"y":0.185516357421875},{"x":-0.2027587890625,"y":0.0091552734375},{"x":-0.2955322265625,"y":0.44287109375},{"x":-0.1297607421875,"y":-0.13262939453125},{"x":0.18756103515625,"y":-0.16204833984375},{"x":-0.8209228515625,"y":-0.61767578125},{"x":-0.5946044921875,"y":0.170196533203125},{"x":-0.2578125,"y":-0.0428466796875},{"x":-0.49237060546875,"y":0.048309326171875},{"x":-0.122802734375,"y":-0.07208251953125},{"x":-0.15679931640625,"y":-0.070709228515625},{"x":-0.616851806640625,"y":0.141815185546875},{"x":-0.245361328125,"y":0.1163330078125},{"x":-0.00384521484375,"y":0.004364013671875},{"x":-0.21209716796875,"y":0.011016845703125},{"x":0.40399169921875,"y":-0.396270751953125}],"optimisedCameraToObject":{"translation":{"x":0.03742692968792968,"y":-0.017590727997023162,"z":0.5043301537547901},"rotation":{"quaternion":{"W":0.9685121738835984,"X":-0.220537664822406,"Y":0.11329957573618059,"Z":-0.022594547394182436}}},"cornersUsed":[false,false,false,false,true,true,true,true,true,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,false,false,true,true,false,false,true,true,true,true,true,true,true,false,false,false,true,true,true,true,false,false,true,true,true,true,false,false,false,false,false,false,true,true,false,false,false,true,true,false,false,false,false,false,false,false,true,true,true,false,false,true,true,false,false,false,false,false,false,true,false,true,true,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false],"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.09083039313554764,"y":0.0,"z":-1.7600689898245037E-4},{"x":0.10596879571676254,"y":0.0,"z":-1.796737196855247E-4},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.13624559342861176,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.15138399600982666,"y":0.0,"z":-1.4667243522126228E-4},{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.18166080117225647,"y":0.0,"z":-8.800344949122518E-5},{"x":0.19679918885231018,"y":0.0,"z":-4.766857091453858E-5},{"x":0.0,"y":0.015138399787247181,"z":-3.620323695940897E-5},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.13624559342861176,"y":0.015138399787247181,"z":-2.0120972476433963E-4},{"x":0.15138399600982666,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.16652239859104156,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.18166080117225647,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.19679918885231018,"y":0.015138399787247181,"z":-8.387180423596874E-5},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138399787247181,"y":0.03027680143713951,"z":-1.1202985479030758E-4},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.09083039313554764,"y":0.03027680143713951,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.03027680143713951,"z":-2.293677971465513E-4},{"x":0.15138399600982666,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.16652239859104156,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.18166080117225647,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.19679918885231018,"y":0.03027680143713951,"z":-1.1202988389413804E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083039313554764,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.04541520029306412,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.04541520029306412,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.04541520029306412,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.060553599148988724,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.18166080117225647,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.19679918885231018,"y":0.07569199800491333,"z":-1.482331135775894E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.09083039313554764,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.10596879571676254,"z":-1.3214279897511005E-4},{"x":0.16652239859104156,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.18166080117225647,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.19679918885231018,"y":0.12110719084739685,"z":-1.1202989844605327E-4}],"locationInImageSpace":[{"x":342.7744445800781,"y":422.9861755371094},{"x":460.25482177734375,"y":406.7327575683594},{"x":480.8957214355469,"y":404.24774169921875},{"x":501.45526123046875,"y":401.1860046386719},{"x":522.2667236328125,"y":398.3022155761719},{"x":543.3924560546875,"y":395.1812744140625},{"x":564.7644653320312,"y":392.3099060058594},{"x":586.5451049804688,"y":389.4791564941406},{"x":608.2172241210938,"y":386.5677185058594},{"x":343.939208984375,"y":442.885986328125},{"x":463.0870056152344,"y":426.6966857910156},{"x":483.6993408203125,"y":424.2520751953125},{"x":504.400146484375,"y":421.4656677246094},{"x":525.5316772460938,"y":418.7244567871094},{"x":547.0831909179688,"y":416.00433349609375},{"x":568.8133544921875,"y":413.165283203125},{"x":590.773681640625,"y":410.3506164550781},{"x":612.6106567382812,"y":407.6275329589844},{"x":344.9212341308594,"y":463.0124206542969},{"x":364.1722412109375,"y":460.38995361328125},{"x":383.8548583984375,"y":457.9842224121094},{"x":403.8147277832031,"y":455.50457763671875},{"x":465.12445068359375,"y":447.9605407714844},{"x":486.25079345703125,"y":444.96917724609375},{"x":507.2002868652344,"y":442.1766662597656},{"x":528.9012451171875,"y":439.9765930175781},{"x":550.60009765625,"y":437.1607666015625},{"x":572.9046630859375,"y":434.4134521484375},{"x":595.0099487304688,"y":431.6478271484375},{"x":617.2257080078125,"y":428.8395080566406},{"x":345.33843994140625,"y":483.772216796875},{"x":365.0399475097656,"y":481.1308898925781},{"x":385.4454345703125,"y":478.8917236328125},{"x":405.3395080566406,"y":476.32177734375},{"x":426.13067626953125,"y":473.98565673828125},{"x":446.715087890625,"y":471.703369140625},{"x":467.3533630371094,"y":468.983642578125},{"x":488.9335632324219,"y":466.1452941894531},{"x":510.3573303222656,"y":463.9790344238281},{"x":532.0797119140625,"y":461.33795166015625},{"x":554.2045288085938,"y":458.861328125},{"x":576.8139038085938,"y":456.12701416015625},{"x":599.2818603515625,"y":453.49395751953125},{"x":622.2294921875,"y":450.6594543457031},{"x":346.1457824707031,"y":505.16302490234375},{"x":366.326904296875,"y":502.4986572265625},{"x":386.6182556152344,"y":500.40948486328125},{"x":407.073486328125,"y":498.1714782714844},{"x":427.81805419921875,"y":496.0325012207031},{"x":448.94415283203125,"y":493.24798583984375},{"x":470.1167297363281,"y":490.9620666503906},{"x":491.8778991699219,"y":488.5472717285156},{"x":513.5202026367188,"y":486.1206970214844},{"x":535.75,"y":483.5254211425781},{"x":558.4537963867188,"y":480.8907470703125},{"x":580.7623901367188,"y":478.5961608886719},{"x":604.0098876953125,"y":476.0467224121094},{"x":627.4522094726562,"y":473.51318359375},{"x":347.0906677246094,"y":526.876708984375},{"x":367.27325439453125,"y":525.0610961914062},{"x":388.06982421875,"y":522.4514770507812},{"x":408.8840026855469,"y":520.1282348632812},{"x":430.07904052734375,"y":518.0780029296875},{"x":451.06036376953125,"y":515.7879638671875},{"x":473.0257568359375,"y":513.3065185546875},{"x":494.55712890625,"y":510.87353515625},{"x":516.8287963867188,"y":508.4520568847656},{"x":539.3373413085938,"y":506.11700439453125},{"x":562.169189453125,"y":504.10076904296875},{"x":585.08984375,"y":501.5392761230469},{"x":608.3443603515625,"y":499.111083984375},{"x":632.026611328125,"y":496.6085205078125},{"x":348.1119689941406,"y":549.591552734375},{"x":369.0688171386719,"y":547.2720947265625},{"x":389.4714660644531,"y":545.078125},{"x":410.92181396484375,"y":542.772216796875},{"x":431.9920959472656,"y":541.032958984375},{"x":453.46063232421875,"y":538.78076171875},{"x":475.9687194824219,"y":536.3364868164062},{"x":497.9583740234375,"y":534.2424926757812},{"x":520.0700073242188,"y":532.10009765625},{"x":543.205078125,"y":529.892578125},{"x":566.1095581054688,"y":527.8761596679688},{"x":589.5203247070312,"y":525.468994140625},{"x":613.3394165039062,"y":522.960205078125},{"x":637.368408203125,"y":520.7373046875},{"x":348.9916076660156,"y":572.2523803710938},{"x":369.76397705078125,"y":570.665771484375},{"x":391.25506591796875,"y":568.421875},{"x":412.4739074707031,"y":566.1716918945312},{"x":434.0899658203125,"y":564.1782836914062},{"x":455.98486328125,"y":562.494873046875},{"x":478.0699157714844,"y":560.147705078125},{"x":500.9654235839844,"y":558.0880737304688},{"x":523.6394653320312,"y":556.0183715820312},{"x":546.9857788085938,"y":553.9234619140625},{"x":570.2828979492188,"y":551.7709350585938},{"x":593.9518432617188,"y":549.853759765625},{"x":618.2899780273438,"y":547.5555419921875},{"x":642.6498413085938,"y":545.1014404296875},{"x":598.8231201171875,"y":574.8338012695312},{"x":623.23046875,"y":572.648193359375},{"x":647.988037109375,"y":570.7882080078125}],"reprojectionErrors":[{"x":-0.114501953125,"y":0.10150146484375},{"x":0.5125732421875,"y":0.01885986328125},{"x":0.4581298828125,"y":-0.135498046875},{"x":0.77618408203125,"y":-0.242645263671875},{"x":-0.443359375,"y":-0.036834716796875},{"x":-0.275543212890625,"y":0.343780517578125},{"x":-0.15423583984375,"y":0.0499267578125},{"x":0.130401611328125,"y":0.06707763671875},{"x":0.23980712890625,"y":0.0078125},{"x":0.18853759765625,"y":-0.104217529296875},{"x":-0.1839599609375,"y":0.13519287109375},{"x":-0.12799072265625,"y":0.085052490234375},{"x":0.0853271484375,"y":-0.133575439453125},{"x":-0.02923583984375,"y":0.211029052734375},{"x":0.2913818359375,"y":0.326446533203125},{"x":0.122802734375,"y":-0.18133544921875},{"x":0.2225341796875,"y":-0.1046142578125},{"x":-0.01318359375,"y":-0.12811279296875},{"x":0.2247314453125,"y":-0.165496826171875},{"x":0.63079833984375,"y":-0.192840576171875},{"x":-0.0986328125,"y":0.069244384765625},{"x":-0.013153076171875,"y":0.33111572265625},{"x":-0.27398681640625,"y":0.172576904296875},{"x":-0.079803466796875,"y":-0.036163330078125},{"x":0.31781005859375,"y":0.16357421875},{"x":0.034698486328125,"y":0.45257568359375},{"x":0.1732177734375,"y":0.0396728515625},{"x":0.28240966796875,"y":0.071319580078125},{"x":0.26251220703125,"y":-0.092193603515625},{"x":0.03570556640625,"y":-0.029205322265625},{"x":0.23223876953125,"y":-0.09912109375},{"x":0.2353515625,"y":2.44140625E-4},{"x":0.0037841796875,"y":-0.055816650390625},{"x":-0.13671875,"y":0.32891845703125},{"x":-0.138916015625,"y":0.11175537109375},{"x":-0.05267333984375,"y":0.016357421875},{"x":3.96728515625E-4,"y":-0.205535888671875},{"x":-0.0679931640625,"y":0.190155029296875},{"x":0.081207275390625,"y":0.058929443359375},{"x":-0.089996337890625,"y":0.027801513671875},{"x":0.12994384765625,"y":-0.020721435546875},{"x":0.0389404296875,"y":0.06976318359375},{"x":-0.2452392578125,"y":0.1695556640625},{"x":0.15106201171875,"y":-0.101318359375},{"x":-0.10174560546875,"y":-0.148406982421875},{"x":-0.25506591796875,"y":-0.242950439453125},{"x":-0.004913330078125,"y":0.03387451171875},{"x":0.113037109375,"y":-0.3243408203125},{"x":-0.128082275390625,"y":0.0853271484375},{"x":-0.127960205078125,"y":0.18231201171875},{"x":-0.245819091796875,"y":-0.0206298828125},{"x":0.11700439453125,"y":-0.01092529296875},{"x":-0.233184814453125,"y":0.16253662109375},{"x":0.126068115234375,"y":0.259429931640625},{"x":0.024658203125,"y":0.316314697265625},{"x":-0.02947998046875,"y":0.2578125},{"x":-0.1182861328125,"y":-0.148895263671875},{"x":-0.002685546875,"y":-0.040252685546875},{"x":0.0770263671875,"y":-0.09527587890625},{"x":0.0316162109375,"y":-0.10675048828125},{"x":-0.062652587890625,"y":-0.3201904296875},{"x":-0.4525146484375,"y":-0.06268310546875},{"x":-0.026611328125,"y":0.04412841796875},{"x":-0.382781982421875,"y":0.23724365234375},{"x":-0.08905029296875,"y":-0.162353515625},{"x":0.08050537109375,"y":-0.075439453125},{"x":-0.511077880859375,"y":0.17669677734375},{"x":-0.30133056640625,"y":0.05120849609375},{"x":0.07379150390625,"y":-0.0535888671875},{"x":-0.28253173828125,"y":-0.12139892578125},{"x":-0.11151123046875,"y":-0.408935546875},{"x":-0.145263671875,"y":-0.33477783203125},{"x":-0.28094482421875,"y":-0.1885986328125},{"x":-0.31512451171875,"y":-0.35833740234375},{"x":0.049652099609375,"y":-0.04241943359375},{"x":0.117523193359375,"y":-0.399169921875},{"x":-0.264892578125,"y":-0.12298583984375},{"x":-0.10235595703125,"y":0.13470458984375},{"x":-0.05999755859375,"y":0.1104736328125},{"x":-0.01495361328125,"y":-0.2493896484375},{"x":0.125946044921875,"y":0.028564453125},{"x":-0.2529296875,"y":-0.0074462890625},{"x":-0.114990234375,"y":-0.0601806640625},{"x":-0.34906005859375,"y":-0.114990234375},{"x":-0.22882080078125,"y":-0.139892578125},{"x":-0.17022705078125,"y":-0.42828369140625},{"x":-0.465576171875,"y":-0.36431884765625},{"x":-0.46209716796875,"y":-0.17352294921875},{"x":-0.51153564453125,"y":-0.43450927734375},{"x":-0.50604248046875,"y":-0.34649658203125},{"x":-0.52081298828125,"y":-0.61212158203125}],"optimisedCameraToObject":{"translation":{"x":-0.03942295159851743,"y":0.08818535212873384,"z":0.5187139392797832},"rotation":{"quaternion":{"W":0.9709184236941156,"X":-0.20193317787513174,"Y":0.11314114367896098,"Z":-0.06115135167435715}}},"cornersUsed":[true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,true,true,true,false,false,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false],"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.015138399787247181,"y":0.0,"z":-4.766853817272931E-5},{"x":0.03027680143713951,"y":0.0,"z":-8.80034567671828E-5},{"x":0.07569199800491333,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.09083039313554764,"y":0.0,"z":-1.7600689898245037E-4},{"x":0.10596879571676254,"y":0.0,"z":-1.796737196855247E-4},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.0,"y":0.015138399787247181,"z":-3.620323695940897E-5},{"x":0.015138399787247181,"y":0.015138399787247181,"z":-8.387177513213828E-5},{"x":0.03027680143713951,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138399787247181,"y":0.03027680143713951,"z":-1.1202985479030758E-4},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083039313554764,"y":0.03027680143713951,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083039313554764,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.07569199800491333,"y":0.12110719084739685,"z":-2.293677971465513E-4},{"x":0.09083039313554764,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.07569199800491333,"y":0.13624559342861176,"z":-2.0120972476433963E-4},{"x":0.09083039313554764,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.13624559342861176,"y":0.13624559342861176,"z":-2.0120973931625485E-4},{"x":0.15138399600982666,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":315.29290771484375,"y":421.31890869140625},{"x":330.87396240234375,"y":407.5302429199219},{"x":345.4388732910156,"y":392.68133544921875},{"x":392.7151184082031,"y":352.5052490234375},{"x":407.53802490234375,"y":337.66510009765625},{"x":423.2727966308594,"y":325.3955078125},{"x":438.67431640625,"y":311.95635986328125},{"x":484.49774169921875,"y":271.3263244628906},{"x":326.07818603515625,"y":436.2390441894531},{"x":341.8666076660156,"y":422.2398376464844},{"x":357.58563232421875,"y":408.187255859375},{"x":404.48394775390625,"y":366.3390808105469},{"x":420.0838317871094,"y":352.4261779785156},{"x":435.81976318359375,"y":338.67950439453125},{"x":451.1897888183594,"y":324.96502685546875},{"x":336.9405822753906,"y":451.8191223144531},{"x":352.9322204589844,"y":437.5078125},{"x":368.9204406738281,"y":423.10491943359375},{"x":384.8755798339844,"y":408.88311767578125},{"x":400.802734375,"y":394.8055725097656},{"x":416.66998291015625,"y":380.48052978515625},{"x":432.371337890625,"y":366.4314880371094},{"x":448.4696044921875,"y":352.22821044921875},{"x":464.24200439453125,"y":338.2129211425781},{"x":348.36553955078125,"y":467.4915466308594},{"x":364.6340637207031,"y":453.0838928222656},{"x":380.88092041015625,"y":438.4759826660156},{"x":396.971923828125,"y":424.0755310058594},{"x":413.0622253417969,"y":409.7403259277344},{"x":429.1858825683594,"y":395.17578125},{"x":445.36407470703125,"y":380.9874267578125},{"x":461.6615295410156,"y":366.5951843261719},{"x":477.5059814453125,"y":352.234619140625},{"x":359.9377136230469,"y":484.2501525878906},{"x":376.42498779296875,"y":469.3724060058594},{"x":392.9847717285156,"y":454.64239501953125},{"x":409.7103576660156,"y":439.9002990722656},{"x":425.9883117675781,"y":425.16644287109375},{"x":442.28704833984375,"y":410.42608642578125},{"x":458.76885986328125,"y":395.9587707519531},{"x":475.1712646484375,"y":381.2016906738281},{"x":491.5317077636719,"y":366.8017578125},{"x":507.9325256347656,"y":352.2386474609375},{"x":372.02874755859375,"y":501.47662353515625},{"x":388.9684143066406,"y":486.34771728515625},{"x":405.7710266113281,"y":471.3106994628906},{"x":422.5150451660156,"y":456.2147216796875},{"x":439.1475830078125,"y":441.1832275390625},{"x":456.0331726074219,"y":426.19091796875},{"x":472.7373352050781,"y":411.2598571777344},{"x":489.2166748046875,"y":396.3513488769531},{"x":505.96160888671875,"y":381.5052795410156},{"x":522.4794311523438,"y":366.8887939453125},{"x":384.6270446777344,"y":519.4572143554688},{"x":401.8417053222656,"y":504.0591125488281},{"x":418.93670654296875,"y":488.52197265625},{"x":435.97125244140625,"y":473.0582580566406},{"x":453.0401916503906,"y":457.92401123046875},{"x":470.0804138183594,"y":442.7356262207031},{"x":486.97528076171875,"y":427.5995178222656},{"x":504.01470947265625,"y":412.0977478027344},{"x":520.8173828125,"y":397.2879943847656},{"x":397.87860107421875,"y":537.8987426757812},{"x":415.2188720703125,"y":522.1643676757812},{"x":432.5986022949219,"y":506.70147705078125},{"x":449.99468994140625,"y":490.8010559082031},{"x":467.2859802246094,"y":475.26043701171875},{"x":484.61376953125,"y":459.8034362792969},{"x":501.9126281738281,"y":444.02410888671875},{"x":518.9378662109375,"y":428.5255432128906},{"x":411.2889099121094,"y":557.1781616210938},{"x":429.1729736328125,"y":541.0665283203125},{"x":446.91796875,"y":525.0857543945312},{"x":464.4822998046875,"y":509.1266784667969},{"x":482.0394592285156,"y":493.2948303222656},{"x":499.8591003417969,"y":477.41363525390625},{"x":517.2202758789062,"y":461.77203369140625},{"x":425.3810119628906,"y":577.1795654296875},{"x":443.6087341308594,"y":560.8740234375},{"x":461.75494384765625,"y":544.3479614257812},{"x":479.6517028808594,"y":528.1582641601562},{"x":497.8642272949219,"y":512.076171875},{"x":515.4520263671875,"y":495.85003662109375},{"x":533.4877319335938,"y":479.80584716796875},{"x":587.4869384765625,"y":431.4142150878906},{"x":605.1578979492188,"y":415.1940002441406},{"x":658.7562866210938,"y":368.0403747558594}],"reprojectionErrors":[{"x":-0.122711181640625,"y":-0.165374755859375},{"x":-0.222503662109375,"y":-0.17083740234375},{"x":-0.03887939453125,"y":-0.389892578125},{"x":0.12744140625,"y":-0.79736328125},{"x":-0.296661376953125,"y":-0.093658447265625},{"x":-0.19439697265625,"y":-0.15228271484375},{"x":0.010772705078125,"y":-0.50360107421875},{"x":-0.185760498046875,"y":-0.1744384765625},{"x":-0.1881103515625,"y":-0.139190673828125},{"x":-0.182891845703125,"y":-0.145538330078125},{"x":-0.12420654296875,"y":-0.015106201171875},{"x":0.08306884765625,"y":-0.139068603515625},{"x":-0.124420166015625,"y":-0.086639404296875},{"x":-0.02801513671875,"y":-0.059478759765625},{"x":0.03759765625,"y":0.058807373046875},{"x":0.03057861328125,"y":-0.176971435546875},{"x":-0.114410400390625,"y":-0.18621826171875},{"x":0.174346923828125,"y":-0.203948974609375},{"x":-0.07666015625,"y":0.01873779296875},{"x":-0.03314208984375,"y":0.104461669921875},{"x":-0.07861328125,"y":0.062957763671875},{"x":-0.306976318359375,"y":0.0545654296875},{"x":0.060791015625,"y":-0.3145751953125},{"x":0.0052490234375,"y":-0.026763916015625},{"x":-0.119293212890625,"y":0.03826904296875},{"x":-0.124053955078125,"y":0.032379150390625},{"x":-0.088165283203125,"y":0.106964111328125},{"x":0.040679931640625,"y":0.139190673828125},{"x":-0.102752685546875,"y":0.1549072265625},{"x":-0.084625244140625,"y":0.132568359375},{"x":0.137908935546875,"y":0.1114501953125},{"x":-0.049713134765625,"y":0.220428466796875},{"x":-0.06591796875,"y":0.075164794921875},{"x":-0.073516845703125,"y":0.00726318359375},{"x":0.043426513671875,"y":-0.089141845703125},{"x":-0.005615234375,"y":0.204498291015625},{"x":0.1600341796875,"y":-0.1689453125},{"x":-0.148406982421875,"y":-0.19403076171875},{"x":-0.075286865234375,"y":-0.09759521484375},{"x":-0.060699462890625,"y":-0.25067138671875},{"x":-0.082183837890625,"y":0.056365966796875},{"x":0.013671875,"y":-0.3306884765625},{"x":-0.142059326171875,"y":-0.160400390625},{"x":-0.178741455078125,"y":-0.098388671875},{"x":-0.05548095703125,"y":-0.03497314453125},{"x":0.053497314453125,"y":-0.074951171875},{"x":-0.122161865234375,"y":-0.04119873046875},{"x":0.1378173828125,"y":-0.22198486328125},{"x":0.012603759765625,"y":-0.46234130859375},{"x":-0.1605224609375,"y":-0.4132080078125},{"x":-0.273193359375,"y":-0.1204833984375},{"x":-0.42132568359375,"y":-0.1185302734375},{"x":-0.25341796875,"y":0.076446533203125},{"x":-0.50335693359375,"y":-0.669952392578125}],"optimisedCameraToObject":{"translation":{"x":-0.05814003396727581,"y":0.08359932270089303,"z":0.5000668757598635},"rotation":{"quaternion":{"W":0.896728613117393,"X":-0.26465684753474183,"Y":0.08933379445465589,"Z":-0.34329873381336923}}},"cornersUsed":[true,true,false,false,false,true,false,true,true,false,false,true,false,false,true,true,true,false,false,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true,true,true,true,true,false,false,true,true,false,false,true],"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.015138395130634308,"y":0.0,"z":-4.7668523620814085E-5},{"x":0.030276797711849213,"y":0.0,"z":-8.800344949122518E-5},{"x":0.04541519284248352,"y":0.0,"z":-1.2100473395548761E-4},{"x":0.060553595423698425,"y":0.0,"z":-1.4667242066934705E-4},{"x":0.07569199800491333,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.09083040058612823,"y":0.0,"z":-1.760069135343656E-4},{"x":0.10596880316734314,"y":0.0,"z":-1.796737196855247E-4},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.0,"y":0.015138399787247181,"z":-3.620323695940897E-5},{"x":0.015138395130634308,"y":0.015138399787247181,"z":-8.387176058022305E-5},{"x":0.030276797711849213,"y":0.015138399787247181,"z":-1.2420667917467654E-4},{"x":0.04541519284248352,"y":0.015138399787247181,"z":-1.572079781908542E-4},{"x":0.060553595423698425,"y":0.015138399787247181,"z":-1.828756503527984E-4},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083040058612823,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596880316734314,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.12110719084739685,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138395130634308,"y":0.03027680143713951,"z":-1.1202984023839235E-4},{"x":0.030276797711849213,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541519284248352,"y":0.03027680143713951,"z":-1.8536605057306588E-4},{"x":0.060553595423698425,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083040058612823,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.10596880316734314,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138395130634308,"y":0.04541520029306412,"z":-1.3214274076744914E-4},{"x":0.030276797711849213,"y":0.04541520029306412,"z":-1.7247766663786024E-4},{"x":0.04541519284248352,"y":0.04541520029306412,"z":-2.0547895110212266E-4},{"x":0.060553595423698425,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083040058612823,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.10596880316734314,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138395130634308,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.030276797711849213,"y":0.060553599148988724,"z":-1.8454540986567736E-4},{"x":0.04541519284248352,"y":0.060553599148988724,"z":-2.17546708881855E-4},{"x":0.060553595423698425,"y":0.060553599148988724,"z":-2.4321438104379922E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596880316734314,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138395130634308,"y":0.07569199800491333,"z":-1.482330699218437E-4},{"x":0.030276797711849213,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.04541519284248352,"y":0.07569199800491333,"z":-2.2156928025651723E-4},{"x":0.060553595423698425,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083040058612823,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596880316734314,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138395130634308,"y":0.09083039313554764,"z":-1.442104985471815E-4},{"x":0.030276797711849213,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541519284248352,"y":0.09083039313554764,"z":-2.17546708881855E-4},{"x":0.060553595423698425,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596880316734314,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.015138395130634308,"y":0.10596879571676254,"z":-1.3214275531936437E-4},{"x":0.030276797711849213,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541519284248352,"y":0.10596879571676254,"z":-2.054789656540379E-4},{"x":0.060553595423698425,"y":0.10596879571676254,"z":-2.311466378159821E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083040058612823,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596880316734314,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.015138395130634308,"y":0.12110719084739685,"z":-1.1202984751434997E-4},{"x":0.030276797711849213,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541519284248352,"y":0.12110719084739685,"z":-1.853660651249811E-4},{"x":0.060553595423698425,"y":0.12110719084739685,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.12110719084739685,"z":-2.293677971465513E-4},{"x":0.09083040058612823,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.10596880316734314,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.12110719084739685,"y":0.12110719084739685,"z":-2.403682447038591E-4},{"x":0.015138395130634308,"y":0.13624559342861176,"z":-8.387177513213828E-5},{"x":0.030276797711849213,"y":0.13624559342861176,"z":-1.2420669372659177E-4},{"x":0.04541519284248352,"y":0.13624559342861176,"z":-1.5720799274276942E-4},{"x":0.060553595423698425,"y":0.13624559342861176,"z":-1.8287566490471363E-4},{"x":0.07569199800491333,"y":0.13624559342861176,"z":-2.0120972476433963E-4},{"x":0.09083040058612823,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.10596880316734314,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.13624559342861176,"z":-2.1221015776973218E-4}],"locationInImageSpace":[{"x":42.943660736083984,"y":235.81753540039062},{"x":64.76944732666016,"y":238.18511962890625},{"x":85.9918441772461,"y":240.5672149658203},{"x":107.02295684814453,"y":242.21990966796875},{"x":127.43121337890625,"y":245.57017517089844},{"x":147.86634826660156,"y":247.78590393066406},{"x":167.95819091796875,"y":249.9010772705078},{"x":186.8430938720703,"y":251.87957763671875},{"x":206.6502685546875,"y":254.2009735107422},{"x":40.16501998901367,"y":255.00013732910156},{"x":61.875274658203125,"y":257.2237243652344},{"x":83.44496154785156,"y":259.7817687988281},{"x":104.36585998535156,"y":261.63922119140625},{"x":125.20450592041016,"y":264.01983642578125},{"x":145.49588012695312,"y":266.10467529296875},{"x":165.05398559570312,"y":268.10406494140625},{"x":185.67323303222656,"y":270.12493896484375},{"x":205.0342559814453,"y":271.4648132324219},{"x":37.30868911743164,"y":274.10260009765625},{"x":59.027732849121094,"y":276.0899658203125},{"x":80.94441223144531,"y":278.31817626953125},{"x":101.88838195800781,"y":280.2178039550781},{"x":122.9339599609375,"y":282.6501770019531},{"x":143.63389587402344,"y":284.6412048339844},{"x":163.368896484375,"y":285.85882568359375},{"x":183.81394958496094,"y":288.3890380859375},{"x":202.36314392089844,"y":290.3094177246094},{"x":34.45012664794922,"y":293.99163818359375},{"x":56.21334457397461,"y":295.6567687988281},{"x":77.97874450683594,"y":297.7824401855469},{"x":99.29908752441406,"y":299.8050842285156},{"x":120.63346099853516,"y":301.4132995605469},{"x":141.27439880371094,"y":303.42205810546875},{"x":161.77410888671875,"y":305.04278564453125},{"x":181.7728729248047,"y":306.7863464355469},{"x":202.1416778564453,"y":308.8076171875},{"x":31.608396530151367,"y":313.2879638671875},{"x":53.44818115234375,"y":315.18218994140625},{"x":75.40428161621094,"y":316.9874572753906},{"x":96.93924713134766,"y":318.7965087890625},{"x":117.37202453613281,"y":320.23748779296875},{"x":139.1352996826172,"y":322.2193908691406},{"x":159.20704650878906,"y":323.7998352050781},{"x":179.9351348876953,"y":325.4576416015625},{"x":199.4601593017578,"y":327.1622314453125},{"x":28.201751708984375,"y":333.34027099609375},{"x":50.61978530883789,"y":334.8735656738281},{"x":72.84522247314453,"y":336.68792724609375},{"x":94.22162628173828,"y":338.1852722167969},{"x":115.1474609375,"y":339.79083251953125},{"x":136.59080505371094,"y":340.35906982421875},{"x":157.31631469726562,"y":342.9120178222656},{"x":177.51736450195312,"y":343.86090087890625},{"x":197.0598907470703,"y":346.095947265625},{"x":25.37320899963379,"y":353.4205017089844},{"x":47.78795623779297,"y":355.07379150390625},{"x":70.16394805908203,"y":356.3779602050781},{"x":91.7781982421875,"y":358.0063171386719},{"x":113.39429473876953,"y":359.3797607421875},{"x":134.33706665039062,"y":360.9725646972656},{"x":155.11610412597656,"y":362.1781311035156},{"x":175.65191650390625,"y":363.9893493652344},{"x":195.85350036621094,"y":364.983154296875},{"x":44.98505783081055,"y":375.0645446777344},{"x":67.38919830322266,"y":376.6589050292969},{"x":89.25773620605469,"y":378.03741455078125},{"x":110.72035217285156,"y":379.1757507324219},{"x":132.17880249023438,"y":380.3443298339844},{"x":153.12269592285156,"y":381.9870300292969},{"x":173.60704040527344,"y":382.7431335449219},{"x":193.20152282714844,"y":384.0321044921875},{"x":41.85401153564453,"y":395.80126953125},{"x":64.67501831054688,"y":397.05059814453125},{"x":86.38931274414062,"y":398.1304626464844},{"x":108.28888702392578,"y":399.16131591796875},{"x":129.84532165527344,"y":400.4811706542969},{"x":150.70509338378906,"y":401.43798828125},{"x":171.54832458496094,"y":402.83282470703125},{"x":191.91139221191406,"y":403.88348388671875},{"x":38.9325065612793,"y":416.6858215332031},{"x":61.75645446777344,"y":417.6645202636719},{"x":83.8613510131836,"y":418.77215576171875},{"x":105.68753814697266,"y":419.8223876953125},{"x":127.04224395751953,"y":420.22705078125},{"x":148.36289978027344,"y":421.44317626953125},{"x":169.11856079101562,"y":422.3404235839844},{"x":189.76947021484375,"y":422.9569091796875}],"reprojectionErrors":[{"x":-0.2898406982421875,"y":-0.2640380859375},{"x":-0.4568023681640625,"y":-0.16387939453125},{"x":0.28424072265625,"y":0.0422210693359375},{"x":0.18595123291015625,"y":-0.0999908447265625},{"x":0.15016555786132812,"y":-0.07818603515625},{"x":-0.0808563232421875,"y":-0.4232177734375},{"x":0.00804901123046875,"y":-0.09942626953125},{"x":-0.14286041259765625,"y":-0.329864501953125},{"x":0.22736358642578125,"y":0.1041259765625},{"x":-0.19364166259765625,"y":-0.04638671875},{"x":0.02471923828125,"y":0.10162353515625},{"x":-0.1849365234375,"y":-0.312591552734375},{"x":-0.3686370849609375,"y":-0.314361572265625},{"x":0.0994415283203125,"y":0.429046630859375},{"x":-0.449310302734375,"y":-0.167877197265625},{"x":0.5972137451171875,"y":-0.18212890625},{"x":0.00109100341796875,"y":-0.469329833984375},{"x":-0.3592681884765625,"y":-0.13702392578125},{"x":-0.324188232421875,"y":-0.07794189453125},{"x":-0.9636383056640625,"y":-0.32208251953125},{"x":-0.16133689880371094,"y":-0.07391357421875},{"x":0.16440200805664062,"y":-0.145172119140625},{"x":0.02388763427734375,"y":-0.154541015625},{"x":-0.03803253173828125,"y":-0.1942138671875},{"x":0.6669082641601562,"y":0.108184814453125},{"x":-0.12731170654296875,"y":-0.199371337890625},{"x":0.1275787353515625,"y":-0.072174072265625},{"x":0.493133544921875,"y":-0.0772705078125},{"x":0.0084228515625,"y":0.931304931640625},{"x":-0.0842742919921875,"y":-0.06793212890625},{"x":0.0284576416015625,"y":0.514251708984375},{"x":0.4872283935546875,"y":-0.2119140625},{"x":-0.04592323303222656,"y":-0.041015625},{"x":-0.0937347412109375,"y":-0.427764892578125},{"x":-0.155670166015625,"y":-0.052032470703125},{"x":-0.09893798828125,"y":0.161834716796875},{"x":-0.19231414794921875,"y":-0.0888671875},{"x":0.03472900390625,"y":0.020294189453125},{"x":-0.1611480712890625,"y":0.13494873046875},{"x":-0.1771087646484375,"y":-0.24383544921875},{"x":-0.0611114501953125,"y":0.2451171875},{"x":-0.1610107421875,"y":-0.032135009765625},{"x":0.0573883056640625,"y":0.124359130859375},{"x":-0.039642333984375,"y":-0.174072265625},{"x":0.01849365234375,"y":-0.144866943359375},{"x":-0.045742034912109375,"y":-0.00103759765625},{"x":-0.0386505126953125,"y":-0.06103515625},{"x":0.06049346923828125,"y":-0.1219482421875},{"x":0.27979278564453125,"y":0.44720458984375}],"optimisedCameraToObject":{"translation":{"x":-0.2691917130177804,"y":-0.05437199594286835,"z":0.5231707944360371},"rotation":{"quaternion":{"W":0.9835011567878835,"X":-0.10615569820677091,"Y":-0.1428916927510533,"Z":0.032224315010044954}}},"cornersUsed":[false,false,false,false,false,true,true,true,false,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,false,true,true,true,true,false,false,false,false,false,true,true,true,true,true,false,true,true,true,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true,true,true,true,true],"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.18166080117225647,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.04541520029306412,"z":-1.3214279897511005E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.18166080117225647,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.060553599148988724,"z":-1.4421054220292717E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.13624559342861176,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.13624559342861176,"y":0.12110719084739685,"z":-2.2936781169846654E-4},{"x":0.15138399600982666,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.16652239859104156,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.13624559342861176,"y":0.13624559342861176,"z":-2.0120973931625485E-4},{"x":0.15138399600982666,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.16652239859104156,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.18166080117225647,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":415.24456787109375,"y":305.4486083984375},{"x":433.210205078125,"y":346.61114501953125},{"x":449.0751953125,"y":345.5312194824219},{"x":385.76611328125,"y":363.67706298828125},{"x":433.782470703125,"y":361.1416931152344},{"x":450.5112609863281,"y":359.82537841796875},{"x":385.2857971191406,"y":378.9815673828125},{"x":402.0686950683594,"y":378.6631164550781},{"x":418.4653625488281,"y":377.2247619628906},{"x":386.421142578125,"y":394.50836181640625},{"x":402.2799377441406,"y":393.8023681640625},{"x":386.04766845703125,"y":409.74884033203125},{"x":403.0951843261719,"y":410.0962829589844},{"x":386.28643798828125,"y":427.0662841796875},{"x":402.9533996582031,"y":425.763671875},{"x":419.62738037109375,"y":424.267822265625},{"x":234.9291229248047,"y":451.77490234375},{"x":386.6434326171875,"y":443.3494873046875},{"x":404.127197265625,"y":442.48175048828125},{"x":421.3000793457031,"y":441.9045104980469},{"x":437.56732177734375,"y":439.6221923828125},{"x":455.66357421875,"y":440.0033874511719}],"reprojectionErrors":[{"x":-0.054718017578125,"y":0.673614501953125}],"optimisedCameraToObject":{"translation":{"x":-0.1454124303567602,"y":0.009976428811875718,"z":0.6762345175248935},"rotation":{"quaternion":{"W":0.9667604071244109,"X":-0.24992526318801275,"Y":0.048454862056485616,"Z":-0.023744565275718645}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,false,false,false,false,false,false,false,false,false,true,false,false,true,true,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,true,false,false,false,false,false,false,false,false,true,true,true,false,true],"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.16652239859104156,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.18166080117225647,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.10596879571676254,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.12110719084739685,"y":0.12110719084739685,"z":-2.403682447038591E-4},{"x":0.19679918885231018,"y":0.12110719084739685,"z":-1.1202989844605327E-4},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.10596879571676254,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":459.0503845214844,"y":255.7950897216797},{"x":460.8182373046875,"y":277.0452575683594},{"x":483.6236572265625,"y":276.2339782714844},{"x":301.48876953125,"y":304.430908203125},{"x":207.8666229248047,"y":330.34716796875},{"x":231.09376525878906,"y":329.1644287109375},{"x":255.01930236816406,"y":328.43597412109375},{"x":278.2096252441406,"y":327.7037353515625},{"x":301.9004821777344,"y":326.81494140625},{"x":231.0047607421875,"y":352.3703918457031},{"x":254.39590454101562,"y":351.19158935546875},{"x":325.40484619140625,"y":348.85919189453125},{"x":395.523193359375,"y":346.2060241699219},{"x":419.0628967285156,"y":345.3354797363281},{"x":254.1528778076172,"y":374.6970520019531},{"x":349.3731384277344,"y":371.0594482421875},{"x":373.01495361328125,"y":370.16998291015625},{"x":396.8268127441406,"y":369.2407531738281},{"x":420.2146911621094,"y":368.28082275390625},{"x":443.6742248535156,"y":367.517333984375},{"x":467.05657958984375,"y":366.64068603515625},{"x":277.9989929199219,"y":397.511474609375},{"x":349.96173095703125,"y":394.845947265625},{"x":373.9201965332031,"y":393.75732421875},{"x":397.63519287109375,"y":392.8481750488281},{"x":204.3361358642578,"y":425.1429748535156},{"x":277.8862609863281,"y":421.69537353515625},{"x":302.2000732421875,"y":420.7810363769531},{"x":326.27569580078125,"y":419.7662353515625},{"x":350.4150695800781,"y":418.8134460449219},{"x":374.683837890625,"y":417.75164794921875},{"x":398.67755126953125,"y":416.83502197265625},{"x":203.70379638671875,"y":449.9243469238281},{"x":228.53549194335938,"y":448.641357421875},{"x":253.2888946533203,"y":447.6372375488281},{"x":277.9111328125,"y":446.3881530761719},{"x":302.1412048339844,"y":445.53887939453125},{"x":375.4747009277344,"y":442.24725341796875},{"x":399.5386047363281,"y":441.2862243652344},{"x":520.551513671875,"y":436.49920654296875},{"x":252.7680206298828,"y":472.6872253417969},{"x":277.4142150878906,"y":471.6868896484375},{"x":302.3121032714844,"y":470.72747802734375},{"x":376.116455078125,"y":467.36761474609375},{"x":400.7468566894531,"y":466.4833984375},{"x":522.7824096679688,"y":461.48681640625}],"reprojectionErrors":[{"x":-0.1773681640625,"y":-0.096160888671875},{"x":0.247406005859375,"y":-0.439910888671875},{"x":-0.13720703125,"y":0.0509033203125},{"x":0.0808563232421875,"y":-0.461883544921875},{"x":0.01470947265625,"y":-0.236236572265625},{"x":0.205413818359375,"y":-0.008026123046875},{"x":0.135162353515625,"y":-0.1622314453125},{"x":0.066650390625,"y":-0.314483642578125}],"optimisedCameraToObject":{"translation":{"x":-0.12280240453634607,"y":-0.02861763115167417,"z":0.45396309766501475},"rotation":{"quaternion":{"W":0.9904192062857176,"X":-0.13613992921934776,"Y":-0.012486794042284735,"Z":-0.019488341824427984}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,true,true,false,false,true,false,false,true,true,false,false,false,false,false,false,true,false,false,false,true,true,true,true,true,true,false,false,false,false,false,true,false,false,true,true,true,false,false,false,false,false,true,false,false,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,true,false,false,true,true,false,false,false,false,true,false,false,true,true,true,false,false,true,true,false,false,false,false,true],"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.015138399787247181,"y":0.0,"z":-4.766853817272931E-5},{"x":0.03027680143713951,"y":0.0,"z":-8.80034567671828E-5},{"x":0.0,"y":0.015138400718569756,"z":-3.6203240597387776E-5},{"x":0.015138399787247181,"y":0.015138400718569756,"z":-8.387177513213828E-5},{"x":0.03027680143713951,"y":0.015138400718569756,"z":-1.2420669372659177E-4},{"x":0.04541520029306412,"y":0.015138400718569756,"z":-1.5720799274276942E-4},{"x":0.060553599148988724,"y":0.015138400718569756,"z":-1.8287566490471363E-4},{"x":0.07569199800491333,"y":0.015138400718569756,"z":-2.012097102124244E-4},{"x":0.09083039313554764,"y":0.015138400718569756,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138400718569756,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.015138400718569756,"z":-2.1221015776973218E-4},{"x":0.0,"y":0.030276799574494362,"z":-6.436130934162065E-5},{"x":0.015138399787247181,"y":0.030276799574494362,"z":-1.1202984751434997E-4},{"x":0.03027680143713951,"y":0.030276799574494362,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.030276799574494362,"z":-1.853660651249811E-4},{"x":0.09083039313554764,"y":0.030276799574494362,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.030276799574494362,"z":-2.4403503630310297E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.09083039313554764,"y":0.04541520029306412,"z":-2.604811161290854E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.15138399600982666,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.04541520029306412,"z":-2.0547898020595312E-4},{"x":0.0,"y":0.06055360287427902,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.06055360287427902,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.06055360287427902,"z":-1.8454542441759259E-4},{"x":0.09083039313554764,"y":0.06055360287427902,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.06055360287427902,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.06055360287427902,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.06055360287427902,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.06055360287427902,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.06055360287427902,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.06055360287427902,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.06055360287427902,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.18166080117225647,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.19679918885231018,"y":0.07569199800491333,"z":-1.482331135775894E-4},{"x":0.0,"y":0.09083040058612823,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.09083040058612823,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.09083040058612823,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083040058612823,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083040058612823,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083040058612823,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.09083040058612823,"z":-2.7254887390881777E-4},{"x":0.16652239859104156,"y":0.09083040058612823,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.09083040058612823,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.09083040058612823,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.10596879571676254,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.12110719829797745,"z":-6.436131661757827E-5},{"x":0.015138399787247181,"y":0.12110719829797745,"z":-1.1202985479030758E-4},{"x":0.03027680143713951,"y":0.12110719829797745,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.12110719829797745,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.12110719829797745,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.12110719829797745,"z":-2.2936778259463608E-4},{"x":0.09083039313554764,"y":0.12110719829797745,"z":-2.4036821560002863E-4},{"x":0.10596879571676254,"y":0.12110719829797745,"z":-2.4403503630310297E-4},{"x":0.12110719084739685,"y":0.12110719829797745,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.12110719829797745,"z":-2.293677971465513E-4},{"x":0.15138399600982666,"y":0.12110719829797745,"z":-2.1103373728692532E-4},{"x":0.16652239859104156,"y":0.12110719829797745,"z":-1.853660651249811E-4},{"x":0.18166080117225647,"y":0.12110719829797745,"z":-1.5236476610880345E-4},{"x":0.19679918885231018,"y":0.12110719829797745,"z":-1.1202988389413804E-4}],"locationInImageSpace":[{"x":89.84513854980469,"y":44.48374938964844},{"x":114.85655212402344,"y":45.37851333618164},{"x":139.82728576660156,"y":46.73008728027344},{"x":89.57010650634766,"y":67.09235382080078},{"x":114.85440063476562,"y":68.05982208251953},{"x":139.67689514160156,"y":69.16963195800781},{"x":164.0467529296875,"y":69.88844299316406},{"x":188.22425842285156,"y":70.42243194580078},{"x":212.6475372314453,"y":71.48052978515625},{"x":236.7676544189453,"y":72.33086395263672},{"x":260.51092529296875,"y":73.49735260009766},{"x":284.07379150390625,"y":74.02632141113281},{"x":89.32404327392578,"y":90.38697052001953},{"x":114.4288101196289,"y":90.83980560302734},{"x":139.34205627441406,"y":91.5943603515625},{"x":163.9855194091797,"y":92.16388702392578},{"x":237.0146026611328,"y":94.68756103515625},{"x":260.7945251464844,"y":95.35595703125},{"x":88.51202392578125,"y":113.2040786743164},{"x":113.96504211425781,"y":114.15188598632812},{"x":139.00540161132812,"y":114.42864227294922},{"x":236.94570922851562,"y":117.05653381347656},{"x":260.9693298339844,"y":117.80135345458984},{"x":331.0879821777344,"y":119.47208404541016},{"x":354.0040588378906,"y":120.16133117675781},{"x":88.17675018310547,"y":136.4105682373047},{"x":113.6041259765625,"y":137.0061492919922},{"x":138.89532470703125,"y":137.54554748535156},{"x":237.18409729003906,"y":139.71702575683594},{"x":261.2226867675781,"y":140.3055419921875},{"x":284.9264221191406,"y":140.69845581054688},{"x":308.6977844238281,"y":141.0904998779297},{"x":331.77703857421875,"y":141.892822265625},{"x":354.53131103515625,"y":142.0728759765625},{"x":377.25537109375,"y":142.85073852539062},{"x":399.7962646484375,"y":143.3336944580078},{"x":87.50408935546875,"y":160.02842712402344},{"x":113.1971206665039,"y":160.4134979248047},{"x":138.34848022460938,"y":160.4881591796875},{"x":163.63897705078125,"y":161.462890625},{"x":237.29896545410156,"y":162.15928649902344},{"x":355.1903381347656,"y":164.5071563720703},{"x":378.2635803222656,"y":164.7843017578125},{"x":400.5794372558594,"y":165.1732177734375},{"x":87.08612060546875,"y":183.69039916992188},{"x":112.83544921875,"y":183.94888305664062},{"x":138.4605255126953,"y":184.2325439453125},{"x":163.5741729736328,"y":184.33946228027344},{"x":188.2486114501953,"y":184.699462890625},{"x":213.1068878173828,"y":185.04483032226562},{"x":237.6880645751953,"y":185.24176025390625},{"x":355.8578796386719,"y":186.69534301757812},{"x":378.6834716796875,"y":187.034912109375},{"x":401.3058776855469,"y":187.0369415283203},{"x":86.46389770507812,"y":207.41287231445312},{"x":112.24982452392578,"y":207.51231384277344},{"x":138.28627014160156,"y":207.8258056640625},{"x":163.44772338867188,"y":208.05357360839844},{"x":188.30239868164062,"y":208.10357666015625},{"x":213.27040100097656,"y":208.2925262451172},{"x":237.85479736328125,"y":208.6721954345703},{"x":262.1484680175781,"y":208.9122314453125},{"x":285.7904357910156,"y":208.87245178222656},{"x":309.8672180175781,"y":209.1800079345703},{"x":333.05853271484375,"y":209.23606872558594},{"x":356.24542236328125,"y":209.20701599121094},{"x":379.31610107421875,"y":209.516845703125},{"x":401.9725646972656,"y":209.60720825195312},{"x":86.19705200195312,"y":231.5227813720703},{"x":112.04492950439453,"y":231.64564514160156},{"x":138.0272216796875,"y":231.68687438964844},{"x":163.1608123779297,"y":231.5714569091797},{"x":188.20098876953125,"y":231.7162628173828},{"x":213.2987060546875,"y":231.76206970214844},{"x":237.85028076171875,"y":231.932861328125},{"x":262.14453125,"y":231.85311889648438},{"x":286.3357849121094,"y":231.92298889160156},{"x":310.043212890625,"y":232.09153747558594},{"x":333.7401123046875,"y":231.89585876464844},{"x":356.8160400390625,"y":232.1086883544922},{"x":380.01031494140625,"y":231.88587951660156},{"x":402.9971008300781,"y":231.9920654296875}],"reprojectionErrors":[{"x":-0.0237884521484375,"y":-0.07427215576171875},{"x":0.111175537109375,"y":0.11244964599609375},{"x":-0.1083831787109375,"y":-0.160125732421875},{"x":0.0140838623046875,"y":-0.2161407470703125},{"x":-0.05914306640625,"y":-0.289154052734375},{"x":-0.0467529296875,"y":-0.1678314208984375},{"x":-0.3485107421875,"y":-0.04693603515625},{"x":-0.201934814453125,"y":-0.33758544921875},{"x":0.028472900390625,"y":-0.00726318359375},{"x":0.05059814453125,"y":-0.2760467529296875},{"x":0.01995849609375,"y":-0.251220703125},{"x":0.0265045166015625,"y":-0.1495208740234375},{"x":-0.250396728515625,"y":-0.1273345947265625},{"x":0.0302734375,"y":-0.12091064453125},{"x":-0.0399627685546875,"y":-0.1082305908203125},{"x":-0.04640960693359375,"y":-0.0913543701171875},{"x":0.1553192138671875,"y":-0.0123443603515625},{"x":-0.0259552001953125,"y":-0.080108642578125},{"x":-0.2882232666015625,"y":-0.03515625},{"x":-0.1382293701171875,"y":-0.1115570068359375},{"x":0.05133056640625,"y":-0.0087127685546875},{"x":0.127532958984375,"y":-0.151947021484375},{"x":-0.196807861328125,"y":-0.2996673583984375},{"x":0.1240234375,"y":-0.1492919921875},{"x":0.237396240234375,"y":-0.07476806640625},{"x":-0.2914581298828125,"y":-0.035003662109375},{"x":-0.005706787109375,"y":0.1044464111328125},{"x":0.1039886474609375,"y":-0.013885498046875},{"x":-0.065826416015625,"y":-0.0909271240234375},{"x":0.0740966796875,"y":-0.2212982177734375},{"x":-0.027252197265625,"y":0.0147552490234375},{"x":0.243408203125,"y":-0.1555023193359375},{"x":0.1495361328125,"y":0.1120147705078125},{"x":0.0196533203125,"y":0.0526580810546875}],"optimisedCameraToObject":{"translation":{"x":-0.19302779085299304,"y":-0.16628172352478715,"z":0.4326618038591473},"rotation":{"quaternion":{"W":0.995170513202104,"X":-0.060940279925585206,"Y":-0.07595528566438424,"Z":-0.012358256968276759}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true,true,true,true,false,false,false,false,false,true,true,true,true,false,false,true,true,false,false,false,false,false,false,true,true,true,false,false,false,true,true,false,false,true,true,false,false,true,true,true,false,false,false,true,true,true,true,true,true,true,true,true,true,true,true,false,false,true,false,false,false,false,true,true,true,true,true,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.015138400718569756,"y":0.0,"z":-4.766853817272931E-5},{"x":0.030276799574494362,"y":0.0,"z":-8.800344949122518E-5},{"x":0.04541520029306412,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.06055360287427902,"y":0.0,"z":-1.4667242066934705E-4},{"x":0.07569199800491333,"y":0.0,"z":-1.6500648052897304E-4},{"x":0.09083040058612823,"y":0.0,"z":-1.760069135343656E-4},{"x":0.10596879571676254,"y":0.0,"z":-1.796737196855247E-4},{"x":0.15138399600982666,"y":0.0,"z":-1.4667243522126228E-4},{"x":0.16652239859104156,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.18166078627109528,"y":0.0,"z":-8.800348587101325E-5},{"x":0.0,"y":0.015138399787247181,"z":-3.620323695940897E-5},{"x":0.015138400718569756,"y":0.015138399787247181,"z":-8.387177513213828E-5},{"x":0.030276799574494362,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.04541520029306412,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.06055360287427902,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.09083040058612823,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.10596879571676254,"y":0.015138399787247181,"z":-2.1587694936897606E-4},{"x":0.15138399600982666,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.16652239859104156,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.18166078627109528,"y":0.015138399787247181,"z":-1.2420672283042222E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138400718569756,"y":0.03027680143713951,"z":-1.1202985479030758E-4},{"x":0.030276799574494362,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.06055360287427902,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.03027680143713951,"z":-2.2936778259463608E-4},{"x":0.09083040058612823,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.10596879571676254,"y":0.03027680143713951,"z":-2.4403503630310297E-4},{"x":0.12110719829797745,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.03027680143713951,"z":-2.293677971465513E-4},{"x":0.15138399600982666,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.16652239859104156,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.18166078627109528,"y":0.03027680143713951,"z":-1.523647952126339E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138400718569756,"y":0.04541520029306412,"z":-1.321427698712796E-4},{"x":0.030276799574494362,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.06055360287427902,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.09083040058612823,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719829797745,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.04541520029306412,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.04541520029306412,"z":-2.0547898020595312E-4},{"x":0.18166078627109528,"y":0.04541520029306412,"z":-1.7247771029360592E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138400718569756,"y":0.060553599148988724,"z":-1.4421051309909672E-4},{"x":0.030276799574494362,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.06055360287427902,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719829797745,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.18166078627109528,"y":0.060553599148988724,"z":-1.8454545352142304E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138400718569756,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.030276799574494362,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.06055360287427902,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083040058612823,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719829797745,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.18166078627109528,"y":0.07569199800491333,"z":-1.885680394480005E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138400718569756,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.030276799574494362,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.06055360287427902,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.09083040058612823,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719829797745,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.18166078627109528,"y":0.09083039313554764,"z":-1.8454545352142304E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138400718569756,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.030276799574494362,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.06055360287427902,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083040058612823,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719829797745,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.18166078627109528,"y":0.10596879571676254,"z":-1.7247771029360592E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138400718569756,"y":0.12110719084739685,"z":-1.1202986934222281E-4},{"x":0.030276799574494362,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.06055360287427902,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.07569199800491333,"y":0.12110719084739685,"z":-2.293677971465513E-4},{"x":0.09083040058612823,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.10596879571676254,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.12110719829797745,"y":0.12110719084739685,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.12110719084739685,"z":-2.2936781169846654E-4},{"x":0.15138399600982666,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.16652239859104156,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.18166078627109528,"y":0.12110719084739685,"z":-1.5236480976454914E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.06055360287427902,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.07569199800491333,"y":0.13624559342861176,"z":-2.0120972476433963E-4},{"x":0.09083040058612823,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.10596879571676254,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719829797745,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.13624559342861176,"y":0.13624559342861176,"z":-2.0120973931625485E-4},{"x":0.15138399600982666,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.16652239859104156,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.18166078627109528,"y":0.13624559342861176,"z":-1.2420673738233745E-4}],"locationInImageSpace":[{"x":39.17151641845703,"y":323.23370361328125},{"x":69.86163330078125,"y":318.97064208984375},{"x":99.99446105957031,"y":314.5672607421875},{"x":129.4698486328125,"y":310.2395935058594},{"x":158.61863708496094,"y":306.052001953125},{"x":186.9306182861328,"y":302.043212890625},{"x":214.86227416992188,"y":298.0179443359375},{"x":242.32376098632812,"y":294.2716369628906},{"x":321.07647705078125,"y":282.88885498046875},{"x":346.4421691894531,"y":279.2837219238281},{"x":371.340087890625,"y":275.77056884765625},{"x":41.991451263427734,"y":351.2996520996094},{"x":72.99131774902344,"y":346.3694763183594},{"x":103.13245391845703,"y":341.8072509765625},{"x":132.7690887451172,"y":337.27984619140625},{"x":162.17210388183594,"y":332.91265869140625},{"x":190.54000854492188,"y":328.2376708984375},{"x":219.0601348876953,"y":324.2601623535156},{"x":246.3241424560547,"y":319.9750671386719},{"x":325.7081298828125,"y":307.94549560546875},{"x":351.23504638671875,"y":304.04949951171875},{"x":376.0793762207031,"y":300.34088134765625},{"x":44.74879837036133,"y":379.5136413574219},{"x":75.80901336669922,"y":374.3301696777344},{"x":106.5994644165039,"y":369.4881591796875},{"x":136.3170928955078,"y":364.7544860839844},{"x":165.9165802001953,"y":359.79998779296875},{"x":194.46209716796875,"y":355.267578125},{"x":222.89337158203125,"y":350.3947448730469},{"x":250.6103057861328,"y":346.0489196777344},{"x":277.78900146484375,"y":341.5914611816406},{"x":304.1627502441406,"y":337.3564147949219},{"x":330.3387451171875,"y":333.3121032714844},{"x":355.8689880371094,"y":329.08203125},{"x":380.9988708496094,"y":325.1272277832031},{"x":47.603546142578125,"y":408.1377258300781},{"x":79.02261352539062,"y":402.7216491699219},{"x":109.84500122070312,"y":397.4296875},{"x":139.7162322998047,"y":392.22491455078125},{"x":169.4086456298828,"y":387.24603271484375},{"x":198.40953063964844,"y":382.3076171875},{"x":226.88597106933594,"y":377.2179260253906},{"x":254.701904296875,"y":372.67169189453125},{"x":281.9798278808594,"y":367.887939453125},{"x":308.73883056640625,"y":363.36444091796875},{"x":334.8026428222656,"y":358.9043273925781},{"x":360.75439453125,"y":354.4738464355469},{"x":385.8128356933594,"y":350.1699523925781},{"x":50.481449127197266,"y":437.3083801269531},{"x":82.0540771484375,"y":431.7572021484375},{"x":113.18767547607422,"y":425.932861328125},{"x":143.28564453125,"y":420.3483581542969},{"x":173.2036590576172,"y":415.07958984375},{"x":202.2880859375,"y":409.85638427734375},{"x":230.96798706054688,"y":404.5475769042969},{"x":259.0675964355469,"y":399.425048828125},{"x":286.3381042480469,"y":394.629638671875},{"x":313.20050048828125,"y":389.6411437988281},{"x":339.7806701660156,"y":385.04949951171875},{"x":365.7013854980469,"y":380.21087646484375},{"x":390.9210510253906,"y":375.7923889160156},{"x":53.649635314941406,"y":466.9408874511719},{"x":85.23328399658203,"y":460.9164123535156},{"x":116.46454620361328,"y":455.0192565917969},{"x":146.88394165039062,"y":449.1644287109375},{"x":177.05172729492188,"y":443.431884765625},{"x":206.14334106445312,"y":437.88348388671875},{"x":235.1621856689453,"y":432.221923828125},{"x":263.09576416015625,"y":426.763916015625},{"x":290.93994140625,"y":421.6300048828125},{"x":317.9030456542969,"y":416.3426513671875},{"x":344.41082763671875,"y":411.1966247558594},{"x":370.3866271972656,"y":406.3551025390625},{"x":396.039794921875,"y":401.645751953125},{"x":56.70054244995117,"y":497.0484619140625},{"x":88.52723693847656,"y":490.7149658203125},{"x":119.71290588378906,"y":484.3636169433594},{"x":150.55136108398438,"y":478.08831787109375},{"x":180.7813262939453,"y":472.0699157714844},{"x":210.25555419921875,"y":466.21099853515625},{"x":239.1253662109375,"y":460.2196044921875},{"x":267.6572265625,"y":454.667236328125},{"x":295.3708190917969,"y":449.2869567871094},{"x":322.5729675292969,"y":443.660888671875},{"x":349.2206115722656,"y":438.3403015136719},{"x":375.594482421875,"y":432.9798278808594},{"x":401.17041015625,"y":428.0036315917969},{"x":59.67277145385742,"y":527.6234741210938},{"x":91.82234191894531,"y":520.8809814453125},{"x":123.30662536621094,"y":514.2711181640625},{"x":154.06724548339844,"y":507.925048828125},{"x":184.6517791748047,"y":501.4294738769531},{"x":214.30809020996094,"y":495.1563720703125},{"x":243.4779815673828,"y":489.018798828125},{"x":271.96063232421875,"y":482.96636962890625},{"x":299.998291015625,"y":477.0646667480469},{"x":327.28125,"y":471.15704345703125},{"x":354.0586242675781,"y":465.4509582519531},{"x":380.4966735839844,"y":460.1003723144531},{"x":406.41455078125,"y":454.7059631347656},{"x":62.839385986328125,"y":559.0115356445312},{"x":95.20453643798828,"y":551.6788940429688},{"x":126.87381744384766,"y":544.8309936523438},{"x":157.94931030273438,"y":537.99267578125},{"x":188.41494750976562,"y":531.3504028320312},{"x":218.1594696044922,"y":524.6863403320312},{"x":247.68157958984375,"y":517.9797973632812},{"x":276.2038879394531,"y":511.71270751953125},{"x":304.5798034667969,"y":505.3286437988281},{"x":332.0699768066406,"y":499.259765625},{"x":359.10009765625,"y":493.5082092285156},{"x":385.71099853515625,"y":487.7696838378906},{"x":411.8456726074219,"y":482.0045166015625},{"x":161.67193603515625,"y":568.5549926757812},{"x":192.6066131591797,"y":561.5014038085938},{"x":222.41822814941406,"y":554.6473388671875},{"x":252.03472900390625,"y":547.7960815429688},{"x":281.00909423828125,"y":541.0855712890625},{"x":309.28533935546875,"y":534.3490600585938},{"x":337.0098571777344,"y":528.1146240234375},{"x":364.1638488769531,"y":521.7708129882812},{"x":391.03277587890625,"y":515.8125},{"x":417.1324157714844,"y":509.7148742675781}],"reprojectionErrors":[{"x":0.092803955078125,"y":-0.367950439453125},{"x":-0.02445220947265625,"y":-0.257537841796875},{"x":-0.0547027587890625,"y":-0.137847900390625},{"x":-0.314239501953125,"y":-0.075469970703125},{"x":-0.278778076171875,"y":-0.111175537109375},{"x":-0.3911590576171875,"y":-0.051788330078125},{"x":-0.54840087890625,"y":-0.194671630859375},{"x":-0.3531494140625,"y":-0.038177490234375},{"x":0.1121063232421875,"y":-0.51959228515625},{"x":-0.06450653076171875,"y":-0.277252197265625},{"x":0.02301025390625,"y":-0.309539794921875},{"x":-0.281890869140625,"y":-0.33343505859375},{"x":-0.1143798828125,"y":0.012908935546875},{"x":-0.6349639892578125,"y":-0.254119873046875},{"x":-0.4218597412109375,"y":-0.13153076171875},{"x":-0.380767822265625,"y":-0.117767333984375},{"x":-0.394073486328125,"y":-0.076171875},{"x":-0.1861572265625,"y":-0.14959716796875},{"x":0.154998779296875,"y":-0.47357177734375},{"x":-0.0653533935546875,"y":-0.432769775390625},{"x":-0.381622314453125,"y":-0.19171142578125},{"x":-0.201934814453125,"y":-0.280548095703125},{"x":-0.5171356201171875,"y":-0.037139892578125},{"x":-0.5609130859375,"y":0.061767578125},{"x":-0.303497314453125,"y":0.021514892578125},{"x":-0.33953857421875,"y":-0.128387451171875},{"x":-0.209014892578125,"y":-0.01336669921875},{"x":-0.145660400390625,"y":-0.096405029296875},{"x":0.15158843994140625,"y":-0.365142822265625},{"x":0.0076141357421875,"y":-0.281097412109375},{"x":-0.15301513671875,"y":-0.214691162109375},{"x":0.0404052734375,"y":-0.13177490234375},{"x":-0.1688232421875,"y":-0.173797607421875},{"x":-0.2528839111328125,"y":-0.157958984375},{"x":-0.3642120361328125,"y":0.10498046875},{"x":-0.32708740234375,"y":0.05902099609375},{"x":-0.29339599609375,"y":0.0286865234375},{"x":-0.062530517578125,"y":0.02142333984375},{"x":-0.205291748046875,"y":0.06884765625},{"x":0.07147216796875,"y":0.071868896484375},{"x":0.177215576171875,"y":-0.32073974609375},{"x":0.10943603515625,"y":-0.438751220703125},{"x":-0.14231109619140625,"y":-0.17010498046875},{"x":0.03521728515625,"y":-0.030792236328125},{"x":-0.1976318359375,"y":-0.09967041015625},{"x":-0.1717529296875,"y":-0.109375},{"x":-0.30120849609375,"y":0.068511962890625},{"x":-0.395843505859375,"y":0.159515380859375},{"x":-0.099700927734375,"y":0.168365478515625},{"x":-0.229278564453125,"y":0.011627197265625},{"x":-0.19171142578125,"y":0.1915283203125},{"x":0.066741943359375,"y":0.038787841796875},{"x":-0.034114837646484375,"y":-0.245391845703125},{"x":0.1194305419921875,"y":-0.237762451171875},{"x":-0.007476806640625,"y":-0.236572265625},{"x":0.061676025390625,"y":-0.16015625},{"x":-0.2169189453125,"y":-0.091583251953125},{"x":-0.00286865234375,"y":-0.095733642578125},{"x":-0.284210205078125,"y":0.121795654296875},{"x":-0.033721923828125,"y":0.24139404296875},{"x":-0.23291015625,"y":0.13983154296875},{"x":0.023529052734375,"y":0.400634765625},{"x":0.1563720703125,"y":0.29998779296875},{"x":0.125213623046875,"y":0.16009521484375},{"x":-0.0736846923828125,"y":-0.141754150390625},{"x":0.07181549072265625,"y":-0.183563232421875},{"x":0.21543121337890625,"y":-0.079010009765625},{"x":0.080841064453125,"y":0.074493408203125},{"x":-0.0538482666015625,"y":0.092742919921875},{"x":-0.0251617431640625,"y":0.06988525390625},{"x":0.03131103515625,"y":0.29473876953125},{"x":-0.13580322265625,"y":0.192840576171875},{"x":-0.031524658203125,"y":0.028106689453125},{"x":0.051422119140625,"y":0.215667724609375},{"x":0.05596923828125,"y":0.32830810546875},{"x":0.246917724609375,"y":0.169403076171875},{"x":0.02109527587890625,"y":0.0086669921875},{"x":0.08139801025390625,"y":0.00616455078125},{"x":0.15380859375,"y":0.00762939453125},{"x":0.31463623046875,"y":-0.122039794921875},{"x":0.033538818359375,"y":0.0269775390625},{"x":0.0793304443359375,"y":0.079193115234375},{"x":0.0262603759765625,"y":0.1181640625},{"x":0.09063720703125,"y":0.191070556640625},{"x":0.045196533203125,"y":0.22918701171875},{"x":0.214111328125,"y":0.38616943359375},{"x":0.36224365234375,"y":0.45159912109375},{"x":0.331573486328125,"y":0.234130859375},{"x":-0.0216064453125,"y":-0.128662109375},{"x":0.063507080078125,"y":0.07781982421875},{"x":0.18083953857421875,"y":-0.05560302734375},{"x":0.246673583984375,"y":-0.0577392578125},{"x":0.294769287109375,"y":-0.11895751953125},{"x":0.4534454345703125,"y":-0.025146484375},{"x":0.2404632568359375,"y":0.2408447265625},{"x":0.4490966796875,"y":0.19354248046875},{"x":0.241241455078125,"y":0.3861083984375},{"x":0.37103271484375,"y":0.38311767578125},{"x":0.427093505859375,"y":0.179351806640625},{"x":0.382354736328125,"y":0.0760498046875},{"x":0.4039459228515625,"y":0.013916015625},{"x":0.1954345703125,"y":-0.0037841796875},{"x":0.490081787109375,"y":-0.07989501953125},{"x":0.3768157958984375,"y":-0.0213623046875},{"x":0.318878173828125,"y":0.02996826171875},{"x":0.38800048828125,"y":0.23748779296875},{"x":0.452911376953125,"y":0.0694580078125},{"x":0.5469970703125,"y":0.13421630859375},{"x":0.398895263671875,"y":-0.06646728515625},{"x":0.506500244140625,"y":-0.010833740234375}],"optimisedCameraToObject":{"translation":{"x":-0.18837712909234292,"y":0.008495932097555557,"z":0.3620946563498533},"rotation":{"quaternion":{"W":0.9840492749490121,"X":-0.10782431261297157,"Y":-0.11104313197718103,"Z":-0.0876947257397055}}},"cornersUsed":[false,true,true,true,true,true,true,true,true,false,false,true,true,true,false,true,true,true,true,true,true,true,true,false,false,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,true,true],"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.03027680143713951,"y":0.0,"z":-8.80034567671828E-5},{"x":0.04541520029306412,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.015138399787247181,"y":0.015138399787247181,"z":-8.387177513213828E-5},{"x":0.03027680143713951,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.04541520029306412,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.060553599148988724,"y":0.015138399787247181,"z":-1.8287566490471363E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.015138399787247181,"y":0.03027680143713951,"z":-1.1202985479030758E-4},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.03027680143713951,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.060553599148988724,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.060553599148988724,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4}],"locationInImageSpace":[{"x":695.8687744140625,"y":331.31121826171875},{"x":720.4450073242188,"y":328.8446044921875},{"x":674.1835327148438,"y":354.9635009765625},{"x":698.5634765625,"y":353.1105651855469},{"x":723.6292724609375,"y":351.0498046875},{"x":749.0966796875,"y":349.057373046875},{"x":652.76123046875,"y":378.4397277832031},{"x":676.867919921875,"y":377.0224914550781},{"x":701.7291259765625,"y":375.2709655761719},{"x":726.8463134765625,"y":373.62725830078125},{"x":752.8696899414062,"y":371.935791015625},{"x":655.311767578125,"y":400.8829650878906},{"x":679.9224243164062,"y":399.4931945800781},{"x":704.8001708984375,"y":398.1195373535156},{"x":730.0814208984375,"y":396.6780700683594},{"x":756.2823486328125,"y":395.3584899902344},{"x":658.0413818359375,"y":423.3209533691406},{"x":682.6307983398438,"y":422.485107421875},{"x":707.8818969726562,"y":421.3363952636719},{"x":733.608154296875,"y":420.1712646484375},{"x":759.9989013671875,"y":419.1002502441406},{"x":660.6958618164062,"y":446.4526062011719},{"x":685.4485473632812,"y":445.858154296875},{"x":710.9008178710938,"y":444.849609375},{"x":737.1593017578125,"y":444.0711364746094},{"x":763.7926635742188,"y":443.37738037109375},{"x":663.311767578125,"y":470.22882080078125},{"x":688.5281372070312,"y":469.6835021972656},{"x":714.2255249023438,"y":469.1806945800781},{"x":740.5036010742188,"y":468.60418701171875},{"x":767.47607421875,"y":468.320068359375},{"x":666.0018920898438,"y":494.060546875},{"x":691.4533081054688,"y":494.17791748046875},{"x":717.442626953125,"y":493.74310302734375},{"x":744.0438842773438,"y":493.3177795410156},{"x":669.0294189453125,"y":518.9141845703125},{"x":694.454833984375,"y":518.883056640625},{"x":720.8811645507812,"y":519.0459594726562},{"x":747.887939453125,"y":518.9967651367188},{"x":671.8126220703125,"y":543.8754272460938},{"x":697.6804809570312,"y":544.1983032226562},{"x":724.2589721679688,"y":544.7203979492188},{"x":751.2757568359375,"y":544.985107421875}],"reprojectionErrors":[{"x":0.2110595703125,"y":-0.141632080078125},{"x":0.14898681640625,"y":-0.162872314453125},{"x":-0.02362060546875,"y":-0.170562744140625},{"x":0.0791015625,"y":0.163421630859375},{"x":0.04302978515625,"y":-0.095184326171875},{"x":-0.06524658203125,"y":-0.06585693359375},{"x":-0.0347900390625,"y":-0.04681396484375},{"x":0.04559326171875,"y":-0.0465087890625},{"x":0.0908203125,"y":-0.352294921875},{"x":0.05902099609375,"y":0.26690673828125},{"x":2.44140625E-4,"y":-0.111602783203125},{"x":0.285888671875,"y":0.051025390625}],"optimisedCameraToObject":{"translation":{"x":0.1752178586904724,"y":0.0195113362166437,"z":0.47158241983605687},"rotation":{"quaternion":{"W":0.9720041589084603,"X":-0.14398321045272952,"Y":0.18360786692350636,"Z":-0.027656850438575794}}},"cornersUsed":[false,false,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,false,false],"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img11.png"},{"locationInObjectSpace":[{"x":0.06055360287427902,"y":0.0,"z":-1.4667242066934705E-4},{"x":0.06055360287427902,"y":0.015138400718569756,"z":-1.8287566490471363E-4},{"x":0.0,"y":0.030276799574494362,"z":-6.436130934162065E-5},{"x":0.06055360287427902,"y":0.030276799574494362,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.030276799574494362,"z":-2.2936778259463608E-4},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.06055360287427902,"y":0.04541520029306412,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.04541520029306412,"z":-2.4948068312369287E-4},{"x":0.030276799574494362,"y":0.06055360287427902,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.06055360287427902,"z":-2.1754672343377024E-4},{"x":0.06055360287427902,"y":0.06055360287427902,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.06055360287427902,"z":-2.615484409034252E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138400718569756,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.06055360287427902,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.015138400718569756,"y":0.09083040058612823,"z":-1.4421051309909672E-4},{"x":0.06055360287427902,"y":0.09083040058612823,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.09083040058612823,"z":-2.615484409034252E-4},{"x":0.015138400718569756,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.030276799574494362,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.06055360287427902,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.0,"y":0.12110719829797745,"z":-6.436131661757827E-5},{"x":0.015138400718569756,"y":0.12110719829797745,"z":-1.1202985479030758E-4},{"x":0.030276799574494362,"y":0.12110719829797745,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.12110719829797745,"z":-1.853660651249811E-4},{"x":0.06055360287427902,"y":0.12110719829797745,"z":-2.1103373728692532E-4},{"x":0.07569199800491333,"y":0.12110719829797745,"z":-2.2936778259463608E-4}],"locationInImageSpace":[{"x":726.3853149414062,"y":115.88086700439453},{"x":726.773193359375,"y":135.99151611328125},{"x":632.8651123046875,"y":162.272705078125},{"x":726.309326171875,"y":157.0055389404297},{"x":751.0694580078125,"y":155.28553771972656},{"x":701.7883911132812,"y":178.75889587402344},{"x":726.3238525390625,"y":177.39154052734375},{"x":751.1889038085938,"y":176.3183135986328},{"x":677.742919921875,"y":200.34829711914062},{"x":701.628173828125,"y":199.29132080078125},{"x":726.2393188476562,"y":198.5946807861328},{"x":751.3489990234375,"y":197.47854614257812},{"x":630.7745971679688,"y":222.37086486816406},{"x":653.803955078125,"y":222.02650451660156},{"x":726.2476806640625,"y":219.85745239257812},{"x":751.3478393554688,"y":219.14500427246094},{"x":653.225341796875,"y":242.61968994140625},{"x":725.9064331054688,"y":241.3304901123047},{"x":751.2797241210938,"y":241.0029296875},{"x":652.5405883789062,"y":263.7134704589844},{"x":676.7761840820312,"y":263.46630859375},{"x":700.971435546875,"y":263.3917541503906},{"x":726.18896484375,"y":263.1636962890625},{"x":751.6013793945312,"y":262.9449462890625},{"x":628.4839477539062,"y":284.8269958496094},{"x":652.0487060546875,"y":284.8564453125},{"x":676.2115478515625,"y":284.9716491699219},{"x":700.8026733398438,"y":285.06134033203125},{"x":726.0464477539062,"y":285.3333435058594},{"x":751.421630859375,"y":285.34490966796875}],"reprojectionErrors":[{"x":0.164306640625,"y":-0.1461181640625}],"optimisedCameraToObject":{"translation":{"x":0.1741760079974631,"y":-0.13340752809940568,"z":0.49641856938546186},"rotation":{"quaternion":{"W":0.9752374878674577,"X":-0.10722800713072572,"Y":0.19106807135000117,"Z":0.030116255665905572}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,true,false,false,false,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,false,false,false,true,true,false,false,true,true,false,false,false,false,false,false,false,false,false,true,false,false,true,true,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,true,true,true,true,true,true,false,false,false,false,false,false,false],"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img12.png"},{"locationInObjectSpace":[{"x":0.18166080117225647,"y":0.0,"z":-8.800344949122518E-5},{"x":0.19679918885231018,"y":0.0,"z":-4.766857091453858E-5},{"x":0.07569199800491333,"y":0.015138399787247181,"z":-2.012097102124244E-4},{"x":0.18166080117225647,"y":0.015138399787247181,"z":-1.2420669372659177E-4},{"x":0.19679918885231018,"y":0.015138399787247181,"z":-8.387180423596874E-5},{"x":0.03027680143713951,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.060553599148988724,"y":0.03027680143713951,"z":-2.1103373728692532E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.13624559342861176,"y":0.03027680143713951,"z":-2.293677971465513E-4},{"x":0.18166080117225647,"y":0.03027680143713951,"z":-1.5236476610880345E-4},{"x":0.19679918885231018,"y":0.03027680143713951,"z":-1.1202988389413804E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.04541520029306412,"z":-1.3214275531936437E-4},{"x":0.060553599148988724,"y":0.04541520029306412,"z":-2.311466378159821E-4},{"x":0.10596879571676254,"y":0.04541520029306412,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.04541520029306412,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.04541520029306412,"z":-2.494807122275233E-4},{"x":0.18166080117225647,"y":0.04541520029306412,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.04541520029306412,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.18166080117225647,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.060553599148988724,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.18166080117225647,"y":0.07569199800491333,"z":-1.885679957922548E-4},{"x":0.19679918885231018,"y":0.07569199800491333,"z":-1.482331135775894E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.09083039313554764,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083039313554764,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.16652239859104156,"y":0.09083039313554764,"z":-2.1754672343377024E-4},{"x":0.18166080117225647,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.19679918885231018,"y":0.09083039313554764,"z":-1.4421054220292717E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.03027680143713951,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.04541520029306412,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.060553599148988724,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.09083039313554764,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.10596879571676254,"y":0.10596879571676254,"z":-2.6414793683215976E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.15138399600982666,"y":0.10596879571676254,"z":-2.3114665236789733E-4},{"x":0.16652239859104156,"y":0.10596879571676254,"z":-2.0547898020595312E-4},{"x":0.18166080117225647,"y":0.10596879571676254,"z":-1.7247768118977547E-4},{"x":0.19679918885231018,"y":0.10596879571676254,"z":-1.3214279897511005E-4},{"x":0.0,"y":0.12110719084739685,"z":-6.436132389353588E-5},{"x":0.015138399787247181,"y":0.12110719084739685,"z":-1.120298620662652E-4},{"x":0.03027680143713951,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.04541520029306412,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.10596879571676254,"y":0.12110719084739685,"z":-2.440350508550182E-4},{"x":0.12110719084739685,"y":0.12110719084739685,"z":-2.403682447038591E-4},{"x":0.13624559342861176,"y":0.12110719084739685,"z":-2.2936781169846654E-4},{"x":0.15138399600982666,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.16652239859104156,"y":0.12110719084739685,"z":-1.8536607967689633E-4},{"x":0.18166080117225647,"y":0.12110719084739685,"z":-1.5236478066071868E-4},{"x":0.19679918885231018,"y":0.12110719084739685,"z":-1.1202989844605327E-4},{"x":0.0,"y":0.13624559342861176,"z":-3.62032515113242E-5},{"x":0.015138399787247181,"y":0.13624559342861176,"z":-8.387178968405351E-5},{"x":0.03027680143713951,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.04541520029306412,"y":0.13624559342861176,"z":-1.5720800729468465E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.10596879571676254,"y":0.13624559342861176,"z":-2.1587696392089128E-4},{"x":0.12110719084739685,"y":0.13624559342861176,"z":-2.1221015776973218E-4},{"x":0.13624559342861176,"y":0.13624559342861176,"z":-2.0120973931625485E-4},{"x":0.18166080117225647,"y":0.13624559342861176,"z":-1.24206708278507E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":423.3897399902344,"y":173.48013305664062},{"x":442.972900390625,"y":172.7267608642578},{"x":290.38787841796875,"y":198.4581298828125},{"x":424.0234680175781,"y":192.596435546875},{"x":443.03521728515625,"y":192.0249481201172},{"x":234.6740264892578,"y":219.08505249023438},{"x":253.085205078125,"y":218.36309814453125},{"x":271.4374694824219,"y":217.64419555664062},{"x":346.87664794921875,"y":214.85775756835938},{"x":366.1274719238281,"y":214.41029357910156},{"x":424.1193542480469,"y":211.9219970703125},{"x":443.55511474609375,"y":211.2221221923828},{"x":196.69229125976562,"y":238.25863647460938},{"x":216.16500854492188,"y":238.31895446777344},{"x":271.68377685546875,"y":236.20614624023438},{"x":327.88983154296875,"y":234.40293884277344},{"x":347.12884521484375,"y":234.09881591796875},{"x":366.1667175292969,"y":233.29840087890625},{"x":424.2355651855469,"y":231.4538116455078},{"x":444.12158203125,"y":230.46688842773438},{"x":197.2330780029297,"y":256.76690673828125},{"x":216.08665466308594,"y":257.00213623046875},{"x":328.0366516113281,"y":253.78515625},{"x":347.00042724609375,"y":253.07435607910156},{"x":366.24505615234375,"y":252.31100463867188},{"x":424.661376953125,"y":250.7879638671875},{"x":444.19866943359375,"y":250.08523559570312},{"x":197.2081298828125,"y":276.2799377441406},{"x":215.76817321777344,"y":276.1237487792969},{"x":233.94638061523438,"y":275.31781005859375},{"x":328.0650634765625,"y":272.8179626464844},{"x":347.2374572753906,"y":272.173583984375},{"x":366.73431396484375,"y":271.9756164550781},{"x":386.0237731933594,"y":271.1842346191406},{"x":405.2734069824219,"y":270.6026306152344},{"x":424.8783874511719,"y":269.904541015625},{"x":444.70416259765625,"y":269.3650207519531},{"x":197.026123046875,"y":295.5208435058594},{"x":214.78485107421875,"y":293.681396484375},{"x":233.7113037109375,"y":293.8584289550781},{"x":252.37889099121094,"y":294.0794372558594},{"x":309.0799560546875,"y":292.6269836425781},{"x":328.1746826171875,"y":292.04620361328125},{"x":347.2156982421875,"y":290.7677001953125},{"x":366.6750793457031,"y":291.1441650390625},{"x":386.10247802734375,"y":290.7586364746094},{"x":405.763671875,"y":290.162109375},{"x":425.1170959472656,"y":289.6654052734375},{"x":444.9590759277344,"y":289.1470642089844},{"x":196.8206787109375,"y":314.405029296875},{"x":215.41165161132812,"y":314.08203125},{"x":233.96974182128906,"y":313.5118408203125},{"x":252.6078643798828,"y":313.0881652832031},{"x":271.1347961425781,"y":312.72113037109375},{"x":290.11065673828125,"y":312.3273620605469},{"x":309.2467041015625,"y":311.80523681640625},{"x":328.2076416015625,"y":311.4145812988281},{"x":347.101806640625,"y":310.500732421875},{"x":366.7896728515625,"y":310.58062744140625},{"x":386.28070068359375,"y":310.12847900390625},{"x":405.8565368652344,"y":309.68939208984375},{"x":425.4317626953125,"y":309.591552734375},{"x":445.2892150878906,"y":308.9874572753906},{"x":196.33749389648438,"y":333.61859130859375},{"x":214.6002655029297,"y":333.1589660644531},{"x":233.46090698242188,"y":332.9014587402344},{"x":252.4772491455078,"y":332.3299560546875},{"x":271.0500183105469,"y":332.12811279296875},{"x":328.1911315917969,"y":331.0886535644531},{"x":347.6840515136719,"y":330.77581787109375},{"x":366.9793701171875,"y":330.3049011230469},{"x":386.5837097167969,"y":328.66925048828125},{"x":404.6912841796875,"y":328.8954162597656},{"x":425.9605407714844,"y":329.022216796875},{"x":445.69464111328125,"y":328.5645446777344},{"x":196.25186157226562,"y":352.6695861816406},{"x":214.72816467285156,"y":352.4706726074219},{"x":233.1695098876953,"y":352.18011474609375},{"x":252.07229614257812,"y":351.9699401855469},{"x":271.19793701171875,"y":351.5841369628906},{"x":328.3217468261719,"y":350.5903625488281},{"x":347.856689453125,"y":349.9689636230469},{"x":367.1235046386719,"y":349.9009094238281},{"x":426.0580139160156,"y":349.033447265625},{"x":446.0525207519531,"y":348.81683349609375}],"reprojectionErrors":[{"x":0.9501800537109375,"y":0.55389404296875},{"x":-0.2587127685546875,"y":-0.1300506591796875},{"x":-0.228118896484375,"y":0.086456298828125},{"x":0.0684814453125,"y":-0.109832763671875},{"x":-0.0919036865234375,"y":0.052764892578125},{"x":-0.07464599609375,"y":-0.12548828125},{"x":-0.093353271484375,"y":-0.008453369140625},{"x":-0.321441650390625,"y":-0.339599609375},{"x":-0.06097412109375,"y":0.136505126953125},{"x":-0.1690673828125,"y":-0.28350830078125},{"x":0.0219879150390625,"y":-0.22479248046875},{"x":-0.1055908203125,"y":-0.170867919921875},{"x":0.0498046875,"y":0.747283935546875},{"x":-0.193328857421875,"y":-0.071929931640625},{"x":-0.2201080322265625,"y":-0.166839599609375},{"x":-0.364898681640625,"y":-0.246978759765625},{"x":-0.36236572265625,"y":-0.08160400390625},{"x":-0.132080078125,"y":-0.121795654296875},{"x":-0.247039794921875,"y":-0.011260986328125},{"x":0.287567138671875,"y":0.464996337890625},{"x":0.009307861328125,"y":-0.283416748046875},{"x":0.23822021484375,"y":-0.170379638671875},{"x":-0.0157318115234375,"y":-0.261077880859375},{"x":0.022125244140625,"y":-0.2135009765625},{"x":-0.168365478515625,"y":-0.258575439453125},{"x":-0.04443359375,"y":-0.14715576171875},{"x":-0.112396240234375,"y":1.127349853515625},{"x":1.4337158203125,"y":0.5384521484375},{"x":0.116119384765625,"y":-0.232391357421875},{"x":-0.018096923828125,"y":-0.31475830078125},{"x":-0.259033203125,"y":-0.222991943359375},{"x":-0.02923583984375,"y":-0.120635986328125},{"x":-0.212249755859375,"y":0.200531005859375},{"x":-0.009674072265625,"y":-0.033203125},{"x":0.170989990234375,"y":-0.08038330078125},{"x":0.11798095703125,"y":-0.1717529296875}],"optimisedCameraToObject":{"translation":{"x":-0.15821167947099832,"y":-0.09974840072298209,"z":0.5508410385166929},"rotation":{"quaternion":{"W":0.9975714434813825,"X":-0.044902712196075355,"Y":0.05254354797316882,"Z":-0.008610293508279004}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,false,true,true,false,false,false,false,false,true,false,false,false,false,false,false,true,true,false,false,true,true,true,false,false,false,true,true,false,false,true,true,false,true,false,false,true,false,false,true,true,true,false,false,true,true,false,true,false,false,false,false,false,true,true,true,false,false,true,true,true,true,true,false,false,false,false,true,true,true,true,true,true,true,true,false,true,true,false,false,true,true,false,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,false,false,true,true,true,false,false,true,true,true,true,true,true,true,false,false,true,true,true,false,false,true,true],"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img13.png"},{"locationInObjectSpace":[{"x":0.04541520029306412,"y":0.0,"z":-1.2100474850740284E-4},{"x":0.0,"y":0.015138399787247181,"z":-3.620323695940897E-5},{"x":0.04541520029306412,"y":0.015138399787247181,"z":-1.5720799274276942E-4},{"x":0.09083039313554764,"y":0.015138399787247181,"z":-2.1221014321781695E-4},{"x":0.0,"y":0.03027680143713951,"z":-6.436131661757827E-5},{"x":0.04541520029306412,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.19679918885231018,"y":0.03027680143713951,"z":-1.1202988389413804E-4},{"x":0.0,"y":0.04541520029306412,"z":-8.447422442259267E-5},{"x":0.04541520029306412,"y":0.04541520029306412,"z":-2.054789656540379E-4},{"x":0.0,"y":0.060553599148988724,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.060553599148988724,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.060553599148988724,"z":-1.8454542441759259E-4},{"x":0.04541520029306412,"y":0.060553599148988724,"z":-2.1754672343377024E-4},{"x":0.10596879571676254,"y":0.060553599148988724,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.0,"y":0.07569199800491333,"z":-1.0056455357698724E-4},{"x":0.015138399787247181,"y":0.07569199800491333,"z":-1.4823308447375894E-4},{"x":0.03027680143713951,"y":0.07569199800491333,"z":-1.8856801034417003E-4},{"x":0.04541520029306412,"y":0.07569199800491333,"z":-2.2156929480843246E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.13624559342861176,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.15138399600982666,"y":0.07569199800491333,"z":-2.472369815222919E-4},{"x":0.16652239859104156,"y":0.07569199800491333,"z":-2.215693093603477E-4},{"x":0.0,"y":0.09083039313554764,"z":-9.65419749263674E-5},{"x":0.015138399787247181,"y":0.09083039313554764,"z":-1.4421051309909672E-4},{"x":0.03027680143713951,"y":0.09083039313554764,"z":-1.8454542441759259E-4},{"x":0.12110719084739685,"y":0.09083039313554764,"z":-2.7254887390881777E-4},{"x":0.13624559342861176,"y":0.09083039313554764,"z":-2.615484409034252E-4},{"x":0.15138399600982666,"y":0.09083039313554764,"z":-2.4321439559571445E-4},{"x":0.0,"y":0.10596879571676254,"z":-8.447422442259267E-5},{"x":0.015138399787247181,"y":0.10596879571676254,"z":-1.321427698712796E-4},{"x":0.07569199800491333,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.12110719084739685,"y":0.10596879571676254,"z":-2.604811452329159E-4},{"x":0.13624559342861176,"y":0.10596879571676254,"z":-2.494807122275233E-4},{"x":0.060553599148988724,"y":0.12110719084739685,"z":-2.1103375183884054E-4},{"x":0.12110719084739685,"y":0.12110719084739685,"z":-2.403682447038591E-4},{"x":0.13624559342861176,"y":0.12110719084739685,"z":-2.2936781169846654E-4},{"x":0.19679918885231018,"y":0.12110719084739685,"z":-1.1202989844605327E-4},{"x":0.060553599148988724,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.15138399600982666,"y":0.13624559342861176,"z":-1.8287567945662886E-4},{"x":0.19679918885231018,"y":0.13624559342861176,"z":-8.387181878788397E-5}],"locationInImageSpace":[{"x":301.60760498046875,"y":45.22820281982422},{"x":243.15762329101562,"y":66.91693115234375},{"x":302.7160339355469,"y":66.0751953125},{"x":362.1037902832031,"y":65.04930114746094},{"x":243.92860412597656,"y":87.1152572631836},{"x":303.1773376464844,"y":86.28119659423828},{"x":500.3439636230469,"y":82.36405181884766},{"x":244.814208984375,"y":107.6163330078125},{"x":303.7970886230469,"y":106.76351928710938},{"x":305.2392272949219,"y":166.33348083496094},{"x":265.3044738769531,"y":127.43755340576172},{"x":284.9887390136719,"y":126.87232971191406},{"x":304.72332763671875,"y":126.81134033203125},{"x":383.1479187011719,"y":125.42845916748047},{"x":402.4729309082031,"y":124.7552261352539},{"x":422.15350341796875,"y":124.56531524658203},{"x":306.0045166015625,"y":186.90203857421875},{"x":265.990966796875,"y":147.3282928466797},{"x":285.4687805175781,"y":146.93075561523438},{"x":305.1423034667969,"y":146.7398681640625},{"x":403.0187683105469,"y":144.837158203125},{"x":422.27679443359375,"y":144.45468139648438},{"x":441.8232421875,"y":144.20404052734375},{"x":461.4884948730469,"y":143.9822998046875},{"x":247.21522521972656,"y":167.75921630859375},{"x":266.58306884765625,"y":167.17857360839844},{"x":286.1919860839844,"y":166.93679809570312},{"x":403.4565124511719,"y":164.78514099121094},{"x":422.4806213378906,"y":164.37503051757812},{"x":441.58917236328125,"y":163.7661895751953},{"x":247.90480041503906,"y":187.33056640625},{"x":267.36773681640625,"y":187.13479614257812},{"x":345.178466796875,"y":185.7676239013672},{"x":403.84735107421875,"y":184.40618896484375},{"x":423.04437255859375,"y":184.5384521484375},{"x":326.3033752441406,"y":205.42123413085938},{"x":403.8284606933594,"y":204.37759399414062},{"x":423.3018493652344,"y":203.8394775390625},{"x":500.69927978515625,"y":202.3909454345703},{"x":326.7899475097656,"y":225.2276611328125},{"x":442.83294677734375,"y":222.90455627441406},{"x":500.8946838378906,"y":221.91018676757812}],"reprojectionErrors":[{"x":-2.20587158203125,"y":-0.5668716430664062},{"x":-1.92242431640625,"y":-0.41704559326171875},{"x":7.547271728515625,"y":3.96075439453125},{"x":-1.819549560546875,"y":0.0994415283203125},{"x":8.65716552734375,"y":2.517578125},{"x":1.10992431640625,"y":1.645294189453125}],"optimisedCameraToObject":{"translation":{"x":-0.11399837940699524,"y":-0.19924717881820653,"z":0.537215032661504},"rotation":{"quaternion":{"W":0.9862009379116198,"X":0.09225346542167978,"Y":0.1373939476741499,"Z":-0.0044622104886915944}}},"cornersUsed":[false,false,false,true,false,false,false,false,false,false,false,false,false,false,true,false,false,true,false,false,true,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,true,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,true,true,true,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,true,false,false,false,false,true,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,true,false,false,true,true,false,false,false,false,false,false,false,false,true,false,false,false,true,true,false,false,false,true,false,false,false,false,true,false,false,false,false,false,true,false,false,true],"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img14.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":-0.0},{"x":0.12110719084739685,"y":0.0,"z":-1.760069135343656E-4},{"x":0.0,"y":0.015138398855924606,"z":-3.620323695940897E-5},{"x":0.015138399787247181,"y":0.015138398855924606,"z":-8.387177513213828E-5},{"x":0.12110719084739685,"y":0.015138398855924606,"z":-2.1221014321781695E-4},{"x":0.12110719084739685,"y":0.03027680143713951,"z":-2.4036823015194386E-4},{"x":0.16652239859104156,"y":0.03027680143713951,"z":-1.853660651249811E-4},{"x":0.16652239859104156,"y":0.04541519656777382,"z":-2.054789656540379E-4},{"x":0.060553599148988724,"y":0.060553599148988724,"z":-2.4321439559571445E-4},{"x":0.07569199800491333,"y":0.060553599148988724,"z":-2.615484409034252E-4},{"x":0.09083039313554764,"y":0.060553599148988724,"z":-2.7254887390881777E-4},{"x":0.07569199800491333,"y":0.07569199800491333,"z":-2.6557102683000267E-4},{"x":0.09083039313554764,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.10596879571676254,"y":0.07569199800491333,"z":-2.8023828053846955E-4},{"x":0.12110719084739685,"y":0.07569199800491333,"z":-2.765714598353952E-4},{"x":0.0,"y":0.09083040058612823,"z":-9.654196765040979E-5},{"x":0.015138399787247181,"y":0.09083040058612823,"z":-1.442104985471815E-4},{"x":0.03027680143713951,"y":0.09083040058612823,"z":-1.8454542441759259E-4},{"x":0.09083039313554764,"y":0.09083040058612823,"z":-2.7254887390881777E-4},{"x":0.10596879571676254,"y":0.09083040058612823,"z":-2.762156946118921E-4},{"x":0.12110719084739685,"y":0.09083040058612823,"z":-2.7254887390881777E-4},{"x":0.19679918885231018,"y":0.09083040058612823,"z":-1.4421054220292717E-4}],"locationInImageSpace":[{"x":114.17156982421875,"y":67.28117370605469},{"x":270.4309997558594,"y":72.11009979248047},{"x":113.83846282958984,"y":86.57022094726562},{"x":133.40855407714844,"y":87.21183776855469},{"x":270.01611328125,"y":91.7333755493164},{"x":269.7028503417969,"y":111.4118881225586},{"x":327.98236083984375,"y":112.9396743774414},{"x":327.69970703125,"y":132.42373657226562},{"x":191.32101440429688,"y":147.1307830810547},{"x":210.68605041503906,"y":148.06642150878906},{"x":230.0892791748047,"y":148.92433166503906},{"x":210.32156372070312,"y":167.81781005859375},{"x":229.60076904296875,"y":168.17388916015625},{"x":249.34869384765625,"y":168.89419555664062},{"x":268.828369140625,"y":169.74481201171875},{"x":111.43255615234375,"y":184.91949462890625},{"x":131.4401092529297,"y":184.6986541748047},{"x":151.146484375,"y":185.2243194580078},{"x":229.64414978027344,"y":187.56214904785156},{"x":248.9082489013672,"y":187.97756958007812},{"x":268.59063720703125,"y":188.58273315429688},{"x":364.78778076171875,"y":191.34783935546875}],"reprojectionErrors":[],"optimisedCameraToObject":{"translation":{"x":-0.21793888425465613,"y":-0.18617200802691564,"z":0.5303268717633165},"rotation":{"quaternion":{"W":0.999790376710533,"X":0.005325900489983016,"Y":-0.01630326977547809,"Z":0.011182165068059568}}},"cornersUsed":[false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,false,true,false,false,false,false,false,true,true,false,false,false,false,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,false,false,false,false,false,true,true,true,false,false,false,true,true,true,false,false,false,false,true],"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/98f92f78-fa5c-4cd5-909e-5be344c42733/imgs/800x600/img15.png"}],"calobjectSize":{"width":14.0,"height":10.0},"calobjectSpacing":0.015138399999999998,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/src/main/deploy/calibrations/right_arducam_800.json b/src/main/deploy/calibrations/right_arducam_800.json deleted file mode 100644 index ff683ef..0000000 --- a/src/main/deploy/calibrations/right_arducam_800.json +++ /dev/null @@ -1 +0,0 @@ -{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[684.9147374097752,0.0,371.8363893896856,0.0,685.7134152700377,296.110092736614,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.04790392233818402,-0.06920591524637874,5.609130214525863E-4,-0.0026251195991928416,0.012128815278404434,-0.001844322544723348,0.003242642793096791,-4.287124080661558E-4]},"calobjectWarp":[-2.2391714350727192E-4,-1.4343522746417786E-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":106.26538848876953,"y":172.49778747558594},{"x":144.2373046875,"y":172.0257110595703},{"x":182.9569854736328,"y":172.08314514160156},{"x":222.75421142578125,"y":172.14108276367188},{"x":262.7756652832031,"y":172.13902282714844},{"x":303.4534912109375,"y":171.98460388183594},{"x":344.9132995605469,"y":172.1147918701172},{"x":104.16173553466797,"y":212.675537109375},{"x":142.37274169921875,"y":212.97708129882812},{"x":180.8836669921875,"y":213.0251007080078},{"x":220.64932250976562,"y":213.31332397460938},{"x":260.2254943847656,"y":213.8289794921875},{"x":301.9626159667969,"y":214.12957763671875},{"x":343.1189270019531,"y":214.73419189453125},{"x":102.10662078857422,"y":253.5009765625},{"x":140.19418334960938,"y":253.99575805664062},{"x":178.9600372314453,"y":254.7830352783203},{"x":218.8439483642578,"y":255.23387145996094},{"x":258.98614501953125,"y":255.99261474609375},{"x":299.958984375,"y":256.9174499511719},{"x":341.7056579589844,"y":257.7732849121094},{"x":100.10343170166016,"y":294.64422607421875},{"x":138.45375061035156,"y":295.24176025390625},{"x":177.15769958496094,"y":296.73486328125},{"x":216.8730926513672,"y":297.6573791503906},{"x":257.0032043457031,"y":298.6906433105469},{"x":297.91375732421875,"y":300.07305908203125},{"x":339.839111328125,"y":300.9164123535156},{"x":98.220458984375,"y":335.0008850097656},{"x":136.12722778320312,"y":336.76531982421875},{"x":175.0268096923828,"y":337.96417236328125},{"x":214.8787078857422,"y":339.4961242675781},{"x":255.21551513671875,"y":340.82794189453125},{"x":296.6320495605469,"y":342.3974609375},{"x":338.2372741699219,"y":343.9622497558594},{"x":95.93185424804688,"y":376.76788330078125},{"x":134.11346435546875,"y":378.8056335449219},{"x":172.84718322753906,"y":380.09686279296875},{"x":213.05792236328125,"y":382.2685241699219},{"x":253.26747131347656,"y":383.9275817871094},{"x":294.50567626953125,"y":386.3393249511719},{"x":336.3748779296875,"y":388.2295227050781},{"x":93.95661926269531,"y":418.0646667480469},{"x":132.08657836914062,"y":420.1647033691406},{"x":170.71168518066406,"y":422.6596374511719},{"x":210.9027099609375,"y":424.997314453125},{"x":251.4449462890625,"y":427.0630798339844},{"x":292.5711669921875,"y":429.25482177734375},{"x":334.8700256347656,"y":432.08349609375}],"reprojectionErrors":[{"x":0.175048828125,"y":0.02569580078125},{"x":-0.05059814453125,"y":0.3511810302734375},{"x":-0.2425689697265625,"y":0.157928466796875},{"x":-0.7171630859375,"y":-0.0247344970703125},{"x":-0.607421875,"y":-0.1359100341796875},{"x":-0.331756591796875,"y":-0.0828857421875},{"x":-0.001953125,"y":-0.3022308349609375},{"x":0.10172271728515625,"y":0.139251708984375},{"x":-0.2750244140625,"y":0.0911407470703125},{"x":-0.166015625,"y":0.3118438720703125},{"x":-0.512451171875,"y":0.3080291748046875},{"x":0.143707275390625,"y":0.0928497314453125},{"x":-0.534149169921875,"y":0.1092071533203125},{"x":0.20977783203125,"y":-0.16156005859375},{"x":-0.0120391845703125,"y":-0.1582183837890625},{"x":-0.1788330078125,"y":0.0051116943359375},{"x":-0.2340545654296875,"y":-0.1041259765625},{"x":-0.603729248046875,"y":0.143402099609375},{"x":-0.41412353515625,"y":0.10382080078125},{"x":-0.22357177734375,"y":-0.0806884765625},{"x":0.03887939453125,"y":-0.17449951171875},{"x":-0.16919708251953125,"y":-0.54144287109375},{"x":-0.51373291015625,"y":-0.07159423828125},{"x":-0.41790771484375,"y":-0.47265625},{"x":-0.5256500244140625,"y":-0.278076171875},{"x":-0.226104736328125,"y":-0.16864013671875},{"x":0.129119873046875,"y":-0.38232421875},{"x":0.32000732421875,"y":-0.030426025390625},{"x":-0.43761444091796875,"y":0.089324951171875},{"x":-0.2551116943359375,"y":-0.1939697265625},{"x":-0.267364501953125,"y":0.1177978515625},{"x":-0.4198150634765625,"y":0.12640380859375},{"x":-0.2308349609375,"y":0.365631103515625},{"x":-0.280914306640625,"y":0.39813232421875},{"x":0.335418701171875,"y":0.46685791015625},{"x":-0.29102325439453125,"y":-0.46771240234375},{"x":-0.301422119140625,"y":-0.60614013671875},{"x":-0.0618438720703125,"y":0.036346435546875},{"x":-0.483001708984375,"y":-0.166656494140625},{"x":-0.07232666015625,"y":0.178375244140625},{"x":0.154815673828125,"y":-0.1932373046875},{"x":0.610687255859375,"y":-0.00677490234375},{"x":-0.44799041748046875,"y":-0.33697509765625},{"x":-0.3263702392578125,"y":-0.115142822265625},{"x":0.106170654296875,"y":-0.248809814453125},{"x":-0.206817626953125,"y":-0.185272216796875},{"x":-0.0361328125,"y":0.190765380859375},{"x":0.40008544921875,"y":0.481964111328125},{"x":0.527923583984375,"y":0.177947998046875}],"optimisedCameraToObject":{"translation":{"x":-0.19036749845810794,"y":-0.10333300905607054,"z":0.4344675123429171},"rotation":{"quaternion":{"W":0.9962619626856976,"X":-0.024641408603911168,"Y":0.08137149124855732,"Z":0.015283425651432496}}},"includeObservationInCalibration":true,"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":295.1114196777344,"y":160.8417510986328},{"x":337.1856994628906,"y":162.0950927734375},{"x":379.71575927734375,"y":163.93040466308594},{"x":422.8009338378906,"y":165.7616424560547},{"x":466.33868408203125,"y":167.17698669433594},{"x":510.4841003417969,"y":168.9625244140625},{"x":555.15966796875,"y":170.68771362304688},{"x":292.63494873046875,"y":203.2911376953125},{"x":334.7442626953125,"y":205.03578186035156},{"x":376.986572265625,"y":206.73216247558594},{"x":420.0962829589844,"y":208.8799285888672},{"x":463.84521484375,"y":210.35694885253906},{"x":507.9684143066406,"y":212.57696533203125},{"x":552.611572265625,"y":214.77685546875},{"x":290.0498962402344,"y":245.7357940673828},{"x":331.9282531738281,"y":247.90228271484375},{"x":374.29705810546875,"y":249.8118438720703},{"x":417.68548583984375,"y":252.00070190429688},{"x":460.9984436035156,"y":254.33306884765625},{"x":505.14019775390625,"y":256.20465087890625},{"x":550.0460815429688,"y":258.7641296386719},{"x":287.3027038574219,"y":288.52728271484375},{"x":329.2394714355469,"y":290.96209716796875},{"x":371.8866882324219,"y":293.0930480957031},{"x":415.1246337890625,"y":295.3936462402344},{"x":458.5348815917969,"y":297.9795837402344},{"x":502.960205078125,"y":300.727294921875},{"x":547.3397827148438,"y":303.03753662109375},{"x":284.571533203125,"y":330.8458557128906},{"x":326.69757080078125,"y":333.2906188964844},{"x":369.0884704589844,"y":336.03375244140625},{"x":412.3104553222656,"y":338.5302734375},{"x":456.02978515625,"y":341.2061462402344},{"x":500.4403076171875,"y":343.9818420410156},{"x":545.0699462890625,"y":347.17205810546875},{"x":281.67559814453125,"y":373.5444641113281},{"x":323.96124267578125,"y":376.7484436035156},{"x":366.3218078613281,"y":379.6494140625},{"x":409.8246154785156,"y":382.625732421875},{"x":453.09356689453125,"y":385.5916442871094},{"x":497.92340087890625,"y":388.9788818359375},{"x":542.902587890625,"y":392.0830078125},{"x":279.04998779296875,"y":416.38616943359375},{"x":321.1944580078125,"y":419.6591796875},{"x":363.9451599121094,"y":422.9556579589844},{"x":407.0330505371094,"y":426.14117431640625},{"x":450.916015625,"y":429.6610412597656},{"x":495.2188415527344,"y":432.9367980957031},{"x":540.317138671875,"y":436.9145202636719}],"reprojectionErrors":[{"x":-0.00714111328125,"y":-0.0254364013671875},{"x":-0.176361083984375,"y":0.2818603515625},{"x":-0.22943115234375,"y":0.04180908203125},{"x":-0.265625,"y":-0.15924072265625},{"x":-0.18280029296875,"y":0.0907440185546875},{"x":-0.13665771484375,"y":0.005950927734375},{"x":-0.05072021484375,"y":0.017120361328125},{"x":-0.209136962890625,"y":-0.190399169921875},{"x":-0.371978759765625,"y":-0.0880279541015625},{"x":-0.09423828125,"y":0.097320556640625},{"x":-0.11029052734375,"y":-0.133819580078125},{"x":-0.19232177734375,"y":0.3408660888671875},{"x":-0.07598876953125,"y":0.1077728271484375},{"x":0.092041015625,"y":-0.0698089599609375},{"x":-0.301361083984375,"y":-0.227386474609375},{"x":-0.194122314453125,"y":-0.258941650390625},{"x":-0.002166748046875,"y":0.0012054443359375},{"x":-0.25469970703125,"y":0.0169677734375},{"x":0.14312744140625,"y":-0.0758056640625},{"x":0.286376953125,"y":0.3272705078125},{"x":0.23883056640625,"y":0.077606201171875},{"x":-0.229827880859375,"y":-0.494720458984375},{"x":-0.144134521484375,"y":-0.5052490234375},{"x":-0.1922607421875,"y":-0.17706298828125},{"x":-0.25445556640625,"y":0.016357421875},{"x":0.08746337890625,"y":-0.040618896484375},{"x":-0.009918212890625,"y":-0.224456787109375},{"x":0.5133056640625,"y":0.064056396484375},{"x":-0.172210693359375,"y":-0.179443359375},{"x":-0.241241455078125,"y":0.090728759765625},{"x":0.0029296875,"y":0.097503662109375},{"x":-0.005889892578125,"y":0.38580322265625},{"x":0.065826416015625,"y":0.52960205078125},{"x":0.023651123046875,"y":0.60833740234375},{"x":0.33868408203125,"y":0.30718994140625},{"x":0.052734375,"y":-0.1414794921875},{"x":-0.1436767578125,"y":-0.338592529296875},{"x":0.1644287109375,"y":-0.197601318359375},{"x":-0.090240478515625,"y":-0.097076416015625},{"x":0.46826171875,"y":0.04864501953125},{"x":0.0445556640625,"y":-0.19232177734375},{"x":0.04931640625,"y":-0.11578369140625},{"x":0.0103759765625,"y":-0.150848388671875},{"x":-0.01495361328125,"y":-0.123870849609375},{"x":-0.0657958984375,"y":-0.085235595703125},{"x":0.12701416015625,"y":0.099334716796875},{"x":0.1053466796875,"y":-0.0157470703125},{"x":0.243896484375,"y":0.147735595703125},{"x":0.1661376953125,"y":-0.356536865234375}],"optimisedCameraToObject":{"translation":{"x":-0.06957634372888649,"y":-0.10766126988800435,"z":0.41314472303589805},"rotation":{"quaternion":{"W":0.998132832074789,"X":-0.011993282902445833,"Y":0.05208579446217053,"Z":0.029564856076558333}}},"includeObservationInCalibration":true,"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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.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.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.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.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.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":546.9029541015625,"y":173.29464721679688},{"x":587.1555786132812,"y":176.4973907470703},{"x":626.540771484375,"y":179.84950256347656},{"x":665.3187866210938,"y":182.93994140625},{"x":703.0034790039062,"y":186.16519165039062},{"x":740.083984375,"y":189.37118530273438},{"x":544.0834350585938,"y":216.06256103515625},{"x":584.2326049804688,"y":219.05882263183594},{"x":623.7393188476562,"y":221.82118225097656},{"x":662.9039306640625,"y":224.76182556152344},{"x":701.0478515625,"y":227.2815704345703},{"x":738.0416870117188,"y":230.20843505859375},{"x":541.292724609375,"y":258.9649353027344},{"x":581.4884033203125,"y":261.4376525878906},{"x":620.8909301757812,"y":263.8662414550781},{"x":659.696533203125,"y":266.4356689453125},{"x":697.6683349609375,"y":268.79791259765625},{"x":734.946533203125,"y":270.75335693359375},{"x":538.3374633789062,"y":301.8629455566406},{"x":578.865478515625,"y":303.8603820800781},{"x":617.9742431640625,"y":306.03851318359375},{"x":657.1041259765625,"y":307.9775390625},{"x":695.1043090820312,"y":309.9665222167969},{"x":732.3194580078125,"y":312.1132507324219},{"x":535.9127197265625,"y":343.8997497558594},{"x":576.132080078125,"y":345.7571716308594},{"x":615.6600341796875,"y":347.2552795410156},{"x":654.2923583984375,"y":348.9859313964844},{"x":692.2953491210938,"y":350.6110534667969},{"x":729.7289428710938,"y":352.1037292480469},{"x":533.0113525390625,"y":386.6262512207031},{"x":573.33349609375,"y":388.01031494140625},{"x":612.7150268554688,"y":389.2283935546875},{"x":651.3096923828125,"y":390.5599060058594},{"x":689.6156616210938,"y":391.9150695800781},{"x":727.0118408203125,"y":393.04150390625},{"x":763.282470703125,"y":394.29180908203125},{"x":530.3983154296875,"y":428.57647705078125},{"x":570.848388671875,"y":429.5242614746094},{"x":610.520263671875,"y":430.87554931640625},{"x":649.0460205078125,"y":431.7014465332031},{"x":687.0743408203125,"y":432.302001953125},{"x":724.4049072265625,"y":433.2821350097656},{"x":760.821533203125,"y":434.2322998046875}],"reprojectionErrors":[{"x":-0.22552490234375,"y":-0.140106201171875},{"x":-0.12457275390625,"y":-0.030548095703125},{"x":0.087646484375,"y":-0.121612548828125},{"x":0.16094970703125,"y":-0.001739501953125},{"x":0.591552734375,"y":-0.066864013671875},{"x":0.90057373046875,"y":-0.162384033203125},{"x":-0.0203857421875,"y":0.0159454345703125},{"x":0.15283203125,"y":-0.061065673828125},{"x":0.21405029296875,"y":0.048004150390625},{"x":-0.12689208984375,"y":-0.0684967041015625},{"x":-0.18145751953125,"y":0.189178466796875},{"x":0.18994140625,"y":-0.0064544677734375},{"x":0.14764404296875,"y":-0.07928466796875},{"x":0.24102783203125,"y":-0.023834228515625},{"x":0.375,"y":0.031341552734375},{"x":0.3634033203125,"y":-0.098175048828125},{"x":0.45318603515625,"y":-0.0638427734375},{"x":0.5140380859375,"y":0.334564208984375},{"x":0.47247314453125,"y":-0.293792724609375},{"x":0.197998046875,"y":-0.15203857421875},{"x":0.59228515625,"y":-0.23199462890625},{"x":0.224853515625,"y":-0.11334228515625},{"x":0.25653076171875,"y":-0.08453369140625},{"x":0.3525390625,"y":-0.25286865234375},{"x":0.2593994140625,"y":0.22259521484375},{"x":0.256103515625,"y":0.11761474609375},{"x":0.1956787109375,"y":0.334259033203125},{"x":0.29229736328125,"y":0.281219482421875},{"x":0.28955078125,"y":0.297149658203125},{"x":0.13739013671875,"y":0.4095458984375},{"x":0.51617431640625,"y":-0.087677001953125},{"x":0.37042236328125,"y":-0.103729248046875},{"x":0.41900634765625,"y":0.011810302734375},{"x":0.517822265625,"y":-0.0198974609375},{"x":0.1785888671875,"y":-0.108489990234375},{"x":0.03228759765625,"y":-0.00103759765625},{"x":0.3045654296875,"y":-0.049560546875},{"x":0.47821044921875,"y":0.234832763671875},{"x":0.16290283203125,"y":0.2730712890625},{"x":-0.118408203125,"y":-0.123321533203125},{"x":0.011962890625,"y":-0.02484130859375},{"x":-0.08489990234375,"y":0.26898193359375},{"x":-0.19891357421875,"y":0.15386962890625},{"x":-0.10400390625,"y":0.039886474609375}],"optimisedCameraToObject":{"translation":{"x":0.07997110450341513,"y":-0.09948533955668773,"z":0.4018712156828376},"rotation":{"quaternion":{"W":0.9967663473113645,"X":0.013950107168127036,"Y":-0.07440944055227902,"Z":0.02693470872786355}}},"includeObservationInCalibration":true,"snapshotName":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":367.3553771972656,"y":196.31065368652344},{"x":406.733642578125,"y":199.09153747558594},{"x":445.41302490234375,"y":201.81582641601562},{"x":484.2298278808594,"y":204.0837860107422},{"x":522.7655639648438,"y":206.94158935546875},{"x":561.7227172851562,"y":209.45388793945312},{"x":599.868896484375,"y":212.190185546875},{"x":364.86602783203125,"y":235.81927490234375},{"x":404.01788330078125,"y":238.02395629882812},{"x":442.447509765625,"y":240.83139038085938},{"x":481.269287109375,"y":243.38124084472656},{"x":519.7448120117188,"y":245.7698516845703},{"x":558.3366088867188,"y":248.60983276367188},{"x":596.3278198242188,"y":251.0729522705078},{"x":362.0566101074219,"y":274.480224609375},{"x":400.8203125,"y":276.6954345703125},{"x":439.7102966308594,"y":279.68890380859375},{"x":477.88677978515625,"y":282.0179748535156},{"x":516.2843627929688,"y":284.7793884277344},{"x":555.0471801757812,"y":287.1521911621094},{"x":593.0676879882812,"y":289.4947814941406},{"x":359.68121337890625,"y":313.329345703125},{"x":397.9988098144531,"y":315.92474365234375},{"x":436.7192687988281,"y":318.3492126464844},{"x":474.91241455078125,"y":320.97314453125},{"x":513.3386840820312,"y":323.07379150390625},{"x":551.8514404296875,"y":325.6566162109375},{"x":589.5569458007812,"y":328.0624694824219},{"x":357.099365234375,"y":351.2790832519531},{"x":395.5191955566406,"y":353.6856689453125},{"x":433.7978515625,"y":356.0232849121094},{"x":472.08612060546875,"y":358.4579162597656},{"x":510.1307067871094,"y":361.0721740722656},{"x":548.2631225585938,"y":363.16693115234375},{"x":586.4135131835938,"y":365.7971496582031},{"x":354.61810302734375,"y":389.55511474609375},{"x":392.7988586425781,"y":392.0729064941406},{"x":430.7272644042969,"y":394.2659606933594},{"x":469.0091247558594,"y":396.6268005371094},{"x":507.07208251953125,"y":398.98992919921875},{"x":545.125732421875,"y":401.66082763671875},{"x":583.0658569335938,"y":404.15289306640625},{"x":351.93914794921875,"y":427.1180114746094},{"x":390.093505859375,"y":429.43389892578125},{"x":428.154541015625,"y":431.86944580078125},{"x":466.3114929199219,"y":434.4603271484375},{"x":504.0509338378906,"y":436.7005615234375},{"x":541.9972534179688,"y":438.92193603515625},{"x":579.9525146484375,"y":441.3321228027344}],"reprojectionErrors":[{"x":-0.0064697265625,"y":-0.0879669189453125},{"x":-0.357391357421875,"y":-0.1941375732421875},{"x":-0.092010498046875,"y":-0.2450714111328125},{"x":-0.055908203125,"y":0.1583404541015625},{"x":0.16021728515625,"y":-0.03076171875},{"x":-0.15533447265625,"y":0.1223602294921875},{"x":0.220947265625,"y":0.04754638671875},{"x":-0.1060791015625,"y":-0.343719482421875},{"x":-0.37548828125,"y":0.0782623291015625},{"x":-0.00439453125,"y":-0.106964111328125},{"x":-0.116424560546875,"y":-0.0396728515625},{"x":0.0177001953125,"y":0.1831512451171875},{"x":-0.07366943359375,"y":-0.05169677734375},{"x":0.3175048828125,"y":0.0833892822265625},{"x":0.133819580078125,"y":-0.048797607421875},{"x":0.10675048828125,"y":0.31512451171875},{"x":-0.127532958984375,"y":-0.106719970703125},{"x":0.261627197265625,"y":0.127716064453125},{"x":0.33050537109375,"y":-0.078857421875},{"x":-0.073974609375,"y":0.0938720703125},{"x":0.1468505859375,"y":0.286956787109375},{"x":-0.0406494140625,"y":-0.241729736328125},{"x":0.23162841796875,"y":-0.305023193359375},{"x":0.020965576171875,"y":-0.2078857421875},{"x":0.2484130859375,"y":-0.321319580078125},{"x":0.14459228515625,"y":0.076904296875},{"x":-0.15289306640625,"y":-0.019287109375},{"x":0.240966796875,"y":0.04876708984375},{"x":0.0111083984375,"y":0.162506103515625},{"x":0.033538818359375,"y":0.24151611328125},{"x":0.117889404296875,"y":0.37603759765625},{"x":0.10430908203125,"y":0.3995361328125},{"x":0.2371826171875,"y":0.228851318359375},{"x":0.1761474609375,"y":0.56256103515625},{"x":-0.01776123046875,"y":0.345184326171875},{"x":-0.017730712890625,"y":-0.064208984375},{"x":0.095306396484375,"y":-0.14239501953125},{"x":0.382232666015625,"y":0.087799072265625},{"x":0.228302001953125,"y":0.133331298828125},{"x":0.196990966796875,"y":0.15911865234375},{"x":0.06988525390625,"y":-0.140777587890625},{"x":-0.05743408203125,"y":-0.2802734375},{"x":0.171234130859375,"y":0.115264892578125},{"x":0.161376953125,"y":0.19354248046875},{"x":0.167205810546875,"y":0.1329345703125},{"x":-0.0093994140625,"y":-0.102752685546875},{"x":0.13616943359375,"y":-0.008026123046875},{"x":-0.0291748046875,"y":0.0848388671875},{"x":-0.316162109375,"y":-0.032318115234375}],"optimisedCameraToObject":{"translation":{"x":-0.026556517013513734,"y":-0.09169131861072553,"z":0.44229082050746893},"rotation":{"quaternion":{"W":0.9988177619922952,"X":0.03444185215253263,"Y":-0.008801893988670333,"Z":0.033156655609667456}}},"includeObservationInCalibration":true,"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":339.06060791015625,"y":292.2277526855469},{"x":376.3753967285156,"y":295.2994079589844},{"x":413.3639831542969,"y":298.71783447265625},{"x":450.476318359375,"y":301.5362854003906},{"x":486.95458984375,"y":304.9813537597656},{"x":523.896240234375,"y":308.00848388671875},{"x":559.9656982421875,"y":311.1206359863281},{"x":335.9451599121094,"y":329.9258117675781},{"x":373.13494873046875,"y":332.853759765625},{"x":410.1759033203125,"y":335.98614501953125},{"x":447.15313720703125,"y":338.95538330078125},{"x":483.89886474609375,"y":341.9346618652344},{"x":520.808349609375,"y":345.0412902832031},{"x":556.8765258789062,"y":347.9783020019531},{"x":332.4299621582031,"y":367.1687316894531},{"x":369.908203125,"y":370.0710144042969},{"x":406.8872985839844,"y":373.02349853515625},{"x":443.78204345703125,"y":376.0458068847656},{"x":480.3359375,"y":379.11102294921875},{"x":517.0509033203125,"y":382.09027099609375},{"x":553.3324584960938,"y":385.21063232421875},{"x":329.1856384277344,"y":404.4607238769531},{"x":366.669921875,"y":407.36090087890625},{"x":403.6183166503906,"y":410.22882080078125},{"x":440.5819396972656,"y":413.077392578125},{"x":477.1147766113281,"y":415.9818115234375},{"x":513.7654418945312,"y":419.2320251464844},{"x":550.2427978515625,"y":422.05621337890625},{"x":325.9815673828125,"y":441.2777099609375},{"x":363.1116638183594,"y":444.0122985839844},{"x":400.2497863769531,"y":447.0605773925781},{"x":437.31353759765625,"y":449.82061767578125},{"x":473.8950500488281,"y":452.83416748046875},{"x":510.6040344238281,"y":455.4580078125},{"x":547.0076293945312,"y":458.55987548828125},{"x":322.50762939453125,"y":478.7712707519531},{"x":360.0099792480469,"y":481.62567138671875},{"x":397.0208740234375,"y":484.18408203125},{"x":434.1093444824219,"y":486.8597717285156},{"x":470.58245849609375,"y":489.8636474609375},{"x":507.36163330078125,"y":492.8047790527344},{"x":543.9049682617188,"y":495.7187805175781},{"x":319.18109130859375,"y":515.9347534179688},{"x":356.81060791015625,"y":518.4778442382812},{"x":394.0828857421875,"y":521.1265869140625},{"x":430.8170471191406,"y":523.997802734375},{"x":467.4473876953125,"y":526.7676391601562},{"x":504.0103759765625,"y":529.2783813476562},{"x":540.6942749023438,"y":532.2147216796875}],"reprojectionErrors":[{"x":-0.121673583984375,"y":-0.06365966796875},{"x":-0.119964599609375,"y":0.112518310546875},{"x":0.042083740234375,"y":-0.0728759765625},{"x":-0.093109130859375,"y":0.3262939453125},{"x":0.224853515625,"y":0.082763671875},{"x":-0.10888671875,"y":0.240447998046875},{"x":0.2342529296875,"y":0.2957763671875},{"x":-0.24798583984375,"y":-0.375579833984375},{"x":-0.12652587890625,"y":-0.137237548828125},{"x":-0.021759033203125,"y":-0.120697021484375},{"x":-0.02642822265625,"y":0.041046142578125},{"x":0.019805908203125,"y":0.174163818359375},{"x":-0.28564453125,"y":0.1607666015625},{"x":0.05511474609375,"y":0.2972412109375},{"x":0.028106689453125,"y":-0.2608642578125},{"x":-0.14599609375,"y":-0.078460693359375},{"x":0.01385498046875,"y":0.033843994140625},{"x":0.085235595703125,"y":0.055816650390625},{"x":0.317230224609375,"y":0.01385498046875},{"x":0.2005615234375,"y":0.0362548828125},{"x":0.3226318359375,"y":-0.1046142578125},{"x":0.0364990234375,"y":-0.229339599609375},{"x":-0.15264892578125,"y":-0.12646484375},{"x":0.029266357421875,"y":-0.013763427734375},{"x":0.02349853515625,"y":0.095306396484375},{"x":0.268646240234375,"y":0.124969482421875},{"x":0.208740234375,"y":-0.215179443359375},{"x":0.12786865234375,"y":-0.153839111328125},{"x":0.00830078125,"y":0.23748779296875},{"x":0.1624755859375,"y":0.424346923828125},{"x":0.1441650390625,"y":0.272552490234375},{"x":0.02813720703125,"y":0.383453369140625},{"x":0.214874267578125,"y":0.21490478515625},{"x":0.08734130859375,"y":0.4095458984375},{"x":0.07122802734375,"y":0.0992431640625},{"x":0.254119873046875,"y":-0.017578125},{"x":0.023284912109375,"y":-0.0321044921875},{"x":0.119842529296875,"y":0.22186279296875},{"x":-0.0328369140625,"y":0.330535888671875},{"x":0.250762939453125,"y":0.082550048828125},{"x":0.0418701171875,"y":-0.131561279296875},{"x":-0.12469482421875,"y":-0.347869873046875},{"x":0.357147216796875,"y":0.006591796875},{"x":-0.015472412109375,"y":0.22186279296875},{"x":-0.19451904296875,"y":0.30145263671875},{"x":-0.00665283203125,"y":0.1280517578125},{"x":0.1063232421875,"y":0.025146484375},{"x":0.1007080078125,"y":0.1500244140625},{"x":-0.21893310546875,"y":-0.18243408203125}],"optimisedCameraToObject":{"translation":{"x":-0.04536870815710916,"y":-0.03017095703489484,"z":0.46287584605236204},"rotation":{"quaternion":{"W":0.9988271621016876,"X":0.004836541699075144,"Y":-0.020965421058413793,"Z":0.043374638120975896}}},"includeObservationInCalibration":true,"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":221.30946350097656,"y":302.67108154296875},{"x":256.391357421875,"y":304.9172058105469},{"x":291.6982116699219,"y":307.3870849609375},{"x":327.6209411621094,"y":310.05615234375},{"x":363.8330078125,"y":313.071533203125},{"x":400.94366455078125,"y":315.8062744140625},{"x":438.015869140625,"y":318.3752746582031},{"x":218.8126983642578,"y":338.8110656738281},{"x":253.8575439453125,"y":341.3642578125},{"x":288.81927490234375,"y":343.9998779296875},{"x":324.8206787109375,"y":347.125244140625},{"x":361.1274108886719,"y":350.0592956542969},{"x":398.0586853027344,"y":353.0224914550781},{"x":435.3100891113281,"y":355.8133544921875},{"x":216.0008087158203,"y":374.9143981933594},{"x":250.92124938964844,"y":377.5718078613281},{"x":286.16070556640625,"y":380.89837646484375},{"x":322.10723876953125,"y":383.91717529296875},{"x":358.3690490722656,"y":387.3333740234375},{"x":395.28997802734375,"y":390.5809326171875},{"x":432.95025634765625,"y":394.11212158203125},{"x":213.41268920898438,"y":411.1982421875},{"x":248.2574462890625,"y":414.56072998046875},{"x":283.7270812988281,"y":417.9544982910156},{"x":319.26348876953125,"y":421.47296142578125},{"x":355.7355651855469,"y":425.0883483886719},{"x":392.7475280761719,"y":428.4670715332031},{"x":430.0685119628906,"y":431.9921875},{"x":210.95437622070312,"y":447.19818115234375},{"x":245.4503173828125,"y":450.7823486328125},{"x":280.9161682128906,"y":454.4261169433594},{"x":316.8917236328125,"y":458.3484802246094},{"x":352.9933166503906,"y":462.0141906738281},{"x":390.0523681640625,"y":465.77716064453125},{"x":427.4768981933594,"y":469.8221130371094},{"x":207.98121643066406,"y":483.9076843261719},{"x":242.7848358154297,"y":487.76690673828125},{"x":278.0449523925781,"y":491.8730163574219},{"x":314.2535400390625,"y":495.68414306640625},{"x":350.1916198730469,"y":499.61358642578125},{"x":387.3416442871094,"y":504.17822265625},{"x":424.7369079589844,"y":508.3167724609375},{"x":205.35462951660156,"y":520.1259155273438},{"x":239.98907470703125,"y":524.2392578125},{"x":275.2627868652344,"y":528.8871459960938},{"x":311.1852722167969,"y":532.9107055664062},{"x":347.7022705078125,"y":537.4143676757812},{"x":384.7498779296875,"y":541.8805541992188},{"x":421.8809814453125,"y":546.6923217773438}],"reprojectionErrors":[{"x":0.3195953369140625,"y":-0.011138916015625},{"x":-0.110565185546875,"y":0.24200439453125},{"x":-0.19647216796875,"y":0.312286376953125},{"x":-0.32354736328125,"y":0.224609375},{"x":-0.15972900390625,"y":-0.167724609375},{"x":-0.308929443359375,"y":-0.237396240234375},{"x":0.171173095703125,"y":-0.098907470703125},{"x":0.046295166015625,"y":-0.106048583984375},{"x":-0.3254852294921875,"y":0.130096435546875},{"x":-0.043701171875,"y":0.32659912109375},{"x":-0.225555419921875,"y":0.076507568359375},{"x":-0.13116455078125,"y":0.061279296875},{"x":-0.07440185546875,"y":0.060760498046875},{"x":0.2545166015625,"y":0.27679443359375},{"x":0.09356689453125,"y":-0.077392578125},{"x":-0.1340789794921875,"y":0.34588623046875},{"x":-0.10906982421875,"y":0.14471435546875},{"x":-0.213836669921875,"y":0.296356201171875},{"x":-0.051025390625,"y":0.096038818359375},{"x":0.040863037109375,"y":0.110076904296875},{"x":-0.012969970703125,"y":-0.113433837890625},{"x":-0.07708740234375,"y":-0.147247314453125},{"x":-0.2108917236328125,"y":-0.13653564453125},{"x":-0.396728515625,"y":-0.11041259765625},{"x":-0.07086181640625,"y":-0.162017822265625},{"x":-0.09661865234375,"y":-0.263214111328125},{"x":-0.072723388671875,"y":-0.08013916015625},{"x":0.23699951171875,"y":0.00445556640625},{"x":-0.3712615966796875,"y":0.14385986328125},{"x":-0.1396942138671875,"y":0.2265625},{"x":-0.3040771484375,"y":0.29827880859375},{"x":-0.3985595703125,"y":0.14031982421875},{"x":-0.033843994140625,"y":0.288238525390625},{"x":-0.035858154296875,"y":0.388427734375},{"x":0.192779541015625,"y":0.256439208984375},{"x":-0.143890380859375,"y":-0.202545166015625},{"x":-0.205047607421875,"y":-0.1002197265625},{"x":-0.147705078125,"y":-0.1942138671875},{"x":-0.458099365234375,"y":0.05767822265625},{"x":0.08837890625,"y":0.242431640625},{"x":0.0147705078125,"y":-0.156585693359375},{"x":0.293212890625,"y":-0.077880859375},{"x":-0.2559661865234375,"y":0.00933837890625},{"x":-0.134613037109375,"y":0.15313720703125},{"x":-0.076507568359375,"y":-0.18499755859375},{"x":-0.08538818359375,"y":0.154052734375},{"x":-0.10137939453125,"y":0.066162109375},{"x":-0.055023193359375,"y":0.06903076171875},{"x":0.506256103515625,"y":-0.22015380859375}],"optimisedCameraToObject":{"translation":{"x":-0.1290530628822834,"y":-0.022425294421625625,"z":0.4870023470641784},"rotation":{"quaternion":{"W":0.996613577856013,"X":-0.013464288198903548,"Y":0.07328200796996563,"Z":0.034782706683400264}}},"includeObservationInCalibration":true,"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":90.03785705566406,"y":310.72601318359375},{"x":123.5698013305664,"y":312.5923767089844},{"x":157.36192321777344,"y":314.1973876953125},{"x":192.54029846191406,"y":316.1217346191406},{"x":227.55335998535156,"y":318.15032958984375},{"x":263.63360595703125,"y":319.9538879394531},{"x":299.928466796875,"y":322.12396240234375},{"x":88.27099609375,"y":347.0223693847656},{"x":121.81598663330078,"y":349.1436767578125},{"x":155.7424774169922,"y":351.2585754394531},{"x":190.23629760742188,"y":353.5048828125},{"x":225.2268524169922,"y":355.7200012207031},{"x":261.3660888671875,"y":358.1160583496094},{"x":297.9971008300781,"y":360.21441650390625},{"x":86.79167938232422,"y":383.2386779785156},{"x":120.0118408203125,"y":385.8603820800781},{"x":153.93344116210938,"y":388.2861633300781},{"x":188.90260314941406,"y":390.78948974609375},{"x":223.84828186035156,"y":393.1882019042969},{"x":259.80389404296875,"y":395.996826171875},{"x":296.0733642578125,"y":398.6301574707031},{"x":85.1788558959961,"y":419.8228759765625},{"x":118.29479217529297,"y":422.493408203125},{"x":152.09910583496094,"y":425.3936767578125},{"x":186.90147399902344,"y":428.1972351074219},{"x":221.836181640625,"y":431.2064208984375},{"x":257.70281982421875,"y":434.24017333984375},{"x":293.98223876953125,"y":437.14129638671875},{"x":83.60932159423828,"y":455.8818054199219},{"x":116.69644927978516,"y":458.8271789550781},{"x":150.2438507080078,"y":462.1194152832031},{"x":184.9669952392578,"y":465.1947937011719},{"x":220.1156463623047,"y":468.3623352050781},{"x":256.05645751953125,"y":471.8955383300781},{"x":292.100341796875,"y":475.28973388671875},{"x":81.90753173828125,"y":492.0986328125},{"x":114.95306396484375,"y":495.67340087890625},{"x":148.51992797851562,"y":499.0736083984375},{"x":183.3359375,"y":502.7611999511719},{"x":218.0794219970703,"y":506.5715637207031},{"x":253.9660186767578,"y":510.3570556640625},{"x":290.19189453125,"y":514.4142456054688},{"x":80.40311431884766,"y":528.0983276367188},{"x":113.1907958984375,"y":531.9303588867188},{"x":146.68115234375,"y":536.1470336914062},{"x":181.0702362060547,"y":540.0050048828125},{"x":216.1864013671875,"y":544.1866455078125},{"x":251.85195922851562,"y":548.3108520507812},{"x":288.1300354003906,"y":552.4865112304688}],"reprojectionErrors":[{"x":0.31475067138671875,"y":0.104095458984375},{"x":-0.05440521240234375,"y":0.0213623046875},{"x":-0.01019287109375,"y":0.234161376953125},{"x":-0.666748046875,"y":0.162384033203125},{"x":-0.46038818359375,"y":0.021728515625},{"x":-0.611358642578125,"y":0.14208984375},{"x":-0.254730224609375,"y":-0.067535400390625},{"x":0.26519012451171875,"y":0.00762939453125},{"x":-0.12104034423828125,"y":0.020904541015625},{"x":-0.2148895263671875,"y":0.078857421875},{"x":-0.190216064453125,"y":0.04425048828125},{"x":0.03570556640625,"y":0.080352783203125},{"x":-0.176849365234375,"y":-0.024383544921875},{"x":-0.15850830078125,"y":0.2093505859375},{"x":-0.05377197265625,"y":0.01678466796875},{"x":-0.12062835693359375,"y":-0.118927001953125},{"x":-0.2147674560546875,"y":-0.01641845703125},{"x":-0.670318603515625,"y":0.051544189453125},{"x":-0.40411376953125,"y":0.267730712890625},{"x":-0.437286376953125,"y":0.118316650390625},{"x":-0.061370849609375,"y":0.18914794921875},{"x":-0.2208099365234375,"y":-0.321502685546875},{"x":-0.1903228759765625,"y":-0.15435791015625},{"x":-0.1738433837890625,"y":-0.1705322265625},{"x":-0.46905517578125,"y":-0.042938232421875},{"x":-0.1980743408203125,"y":-0.073211669921875},{"x":-0.14825439453125,"y":-0.079559326171875},{"x":0.212066650390625,"y":0.095947265625},{"x":-0.4124298095703125,"y":-0.11932373046875},{"x":-0.36145782470703125,"y":0.12493896484375},{"x":-0.096221923828125,"y":0.07275390625},{"x":-0.3202056884765625,"y":0.28863525390625},{"x":-0.2710113525390625,"y":0.464263916015625},{"x":-0.3029937744140625,"y":0.326904296875},{"x":0.285400390625,"y":0.3819580078125},{"x":-0.4528350830078125,"y":-0.06500244140625},{"x":-0.37000274658203125,"y":-0.098114013671875},{"x":-0.133880615234375,"y":0.09783935546875},{"x":-0.460296630859375,"y":0.06170654296875},{"x":-0.015380859375,"y":-0.041107177734375},{"x":-0.002471923828125,"y":-0.062225341796875},{"x":0.39471435546875,"y":-0.29736328125},{"x":-0.67138671875,"y":0.21124267578125},{"x":-0.3418731689453125,"y":0.27288818359375},{"x":-0.040374755859375,"y":0.00848388671875},{"x":0.049041748046875,"y":0.1622314453125},{"x":0.1102142333984375,"y":0.052490234375},{"x":0.3331298828125,"y":0.06121826171875},{"x":0.667144775390625,"y":0.080322265625}],"optimisedCameraToObject":{"translation":{"x":-0.22137176650342022,"y":-0.016187657334579206,"z":0.48572507003640303},"rotation":{"quaternion":{"W":0.9957062261574929,"X":-0.005003618327433362,"Y":0.08952528061073889,"Z":0.02300650182894953}}},"includeObservationInCalibration":true,"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":100.60881805419922,"y":106.35810852050781},{"x":134.24545288085938,"y":105.85897064208984},{"x":168.5045166015625,"y":105.46611785888672},{"x":203.2729949951172,"y":105.12342071533203},{"x":238.26821899414062,"y":104.8594970703125},{"x":273.5412902832031,"y":104.19483947753906},{"x":309.02447509765625,"y":103.86144256591797},{"x":103.160400390625,"y":142.52784729003906},{"x":137.10281372070312,"y":142.42019653320312},{"x":171.01174926757812,"y":142.2108917236328},{"x":205.05389404296875,"y":142.06207275390625},{"x":239.34983825683594,"y":141.52191162109375},{"x":274.89947509765625,"y":141.5987548828125},{"x":309.9424743652344,"y":141.15638732910156},{"x":106.41924285888672,"y":178.23939514160156},{"x":139.53018188476562,"y":178.255615234375},{"x":173.10044860839844,"y":178.14947509765625},{"x":207.24412536621094,"y":178.1393280029297},{"x":241.2316131591797,"y":178.1968994140625},{"x":275.9998474121094,"y":178.00994873046875},{"x":310.8657531738281,"y":178.0529022216797},{"x":109.19105529785156,"y":213.11158752441406},{"x":142.28549194335938,"y":213.2199249267578},{"x":175.31932067871094,"y":213.21669006347656},{"x":209.052734375,"y":213.772705078125},{"x":242.93116760253906,"y":213.88784790039062},{"x":277.0687255859375,"y":213.8684844970703},{"x":311.75323486328125,"y":213.96372985839844},{"x":112.26685333251953,"y":246.92816162109375},{"x":144.78172302246094,"y":247.1885528564453},{"x":177.6352996826172,"y":247.8976593017578},{"x":211.0437469482422,"y":248.02745056152344},{"x":244.48867797851562,"y":248.15513610839844},{"x":278.5101318359375,"y":248.3973388671875},{"x":312.2657165527344,"y":248.80703735351562},{"x":114.79291534423828,"y":280.9228820800781},{"x":147.14212036132812,"y":281.2057189941406},{"x":179.7499237060547,"y":281.90570068359375},{"x":212.89447021484375,"y":282.06036376953125},{"x":245.861083984375,"y":282.670654296875},{"x":279.33526611328125,"y":283.0027160644531},{"x":313.04229736328125,"y":283.33135986328125},{"x":117.60826110839844,"y":313.4248352050781},{"x":149.4197998046875,"y":314.0152893066406},{"x":181.60345458984375,"y":314.96502685546875},{"x":214.1979522705078,"y":315.2834167480469},{"x":247.1965789794922,"y":315.859619140625},{"x":280.1527099609375,"y":316.1675720214844},{"x":313.9950866699219,"y":316.99908447265625}],"reprojectionErrors":[{"x":-0.23943328857421875,"y":0.1803131103515625},{"x":-0.0606231689453125,"y":0.22280120849609375},{"x":-0.10491943359375,"y":0.15741729736328125},{"x":-0.2601776123046875,"y":0.04036712646484375},{"x":-0.244842529296875,"y":-0.15688323974609375},{"x":-0.11126708984375,"y":0.04524993896484375},{"x":0.206787109375,"y":-0.08514404296875},{"x":0.1674041748046875,"y":0.2610321044921875},{"x":-0.291595458984375,"y":0.116668701171875},{"x":-0.3257904052734375,"y":0.0720062255859375},{"x":-0.102783203125,"y":-0.0350494384765625},{"x":0.255706787109375,"y":0.247314453125},{"x":-0.25152587890625,"y":-0.0891876220703125},{"x":0.13427734375,"y":0.0916748046875},{"x":-0.17758941650390625,"y":0.0635833740234375},{"x":-0.13214111328125,"y":-0.0081939697265625},{"x":-0.1624755859375,"y":0.0400390625},{"x":-0.383636474609375,"y":-0.0100860595703125},{"x":-0.0671844482421875,"y":-0.1303253173828125},{"x":-0.15142822265625,"y":-0.0084686279296875},{"x":0.045166015625,"y":-0.11895751953125},{"x":-0.0791778564453125,"y":-0.01336669921875},{"x":-0.3393402099609375,"y":0.0113067626953125},{"x":-0.162933349609375,"y":0.1447906494140625},{"x":-0.3111419677734375,"y":-0.2838134765625},{"x":-0.230621337890625,"y":-0.274444580078125},{"x":-0.036865234375,"y":-0.1335601806640625},{"x":-0.019287109375,"y":-0.1103363037109375},{"x":-0.32744598388671875,"y":0.2634124755859375},{"x":-0.325347900390625,"y":0.317047119140625},{"x":-0.293365478515625,"y":-0.0812530517578125},{"x":-0.4487457275390625,"y":0.0964508056640625},{"x":-0.2743072509765625,"y":0.2728118896484375},{"x":-0.311553955078125,"y":0.3311004638671875},{"x":0.28033447265625,"y":0.2182159423828125},{"x":-0.0677642822265625,"y":-0.3233642578125},{"x":-0.21258544921875,"y":-0.118438720703125},{"x":-0.2546234130859375,"y":-0.3343505859375},{"x":-0.4731292724609375,"y":-0.008758544921875},{"x":-0.154693603515625,"y":-0.142791748046875},{"x":0.01373291015625,"y":-0.00274658203125},{"x":0.305206298828125,"y":0.13641357421875},{"x":-0.138275146484375,"y":-0.08673095703125},{"x":-0.0533905029296875,"y":-0.022705078125},{"x":0.0137176513671875,"y":-0.322113037109375},{"x":0.023193359375,"y":0.005462646484375},{"x":-0.0195159912109375,"y":0.0706787109375},{"x":0.3306884765625,"y":0.3994140625},{"x":0.1434326171875,"y":0.199615478515625}],"optimisedCameraToObject":{"translation":{"x":-0.22047385850192655,"y":-0.1614092023625872,"z":0.4899358736118981},"rotation":{"quaternion":{"W":0.9933996380171577,"X":0.10172414109068803,"Y":0.05293082786767422,"Z":0.0027723217678596816}}},"includeObservationInCalibration":true,"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":243.2695770263672,"y":81.22762298583984},{"x":279.8285217285156,"y":82.23822784423828},{"x":316.10614013671875,"y":83.77398681640625},{"x":352.95391845703125,"y":84.47020721435547},{"x":389.87567138671875,"y":85.77462005615234},{"x":427.1100158691406,"y":86.99259185791016},{"x":464.104736328125,"y":87.92891693115234},{"x":243.7480926513672,"y":119.14984130859375},{"x":279.82269287109375,"y":120.49337005615234},{"x":315.6341552734375,"y":121.35456085205078},{"x":351.994384765625,"y":123.01411437988281},{"x":388.28546142578125,"y":123.7025146484375},{"x":425.20965576171875,"y":125.00679016113281},{"x":461.677978515625,"y":126.26045989990234},{"x":244.11563110351562,"y":156.4071807861328},{"x":279.2550048828125,"y":157.36131286621094},{"x":315.2771911621094,"y":158.77676391601562},{"x":351.260986328125,"y":160.11602783203125},{"x":387.0486755371094,"y":161.2786407470703},{"x":423.3376770019531,"y":162.6897430419922},{"x":459.3424072265625,"y":163.77529907226562},{"x":244.7848663330078,"y":193.2002410888672},{"x":279.6170349121094,"y":194.09181213378906},{"x":314.87432861328125,"y":195.18780517578125},{"x":350.1983947753906,"y":196.8892364501953},{"x":385.9397277832031,"y":197.94764709472656},{"x":421.71514892578125,"y":199.32228088378906},{"x":457.51824951171875,"y":200.42483520507812},{"x":244.8019256591797,"y":227.90902709960938},{"x":279.4519958496094,"y":229.16551208496094},{"x":314.3529357910156,"y":230.55235290527344},{"x":349.50048828125,"y":231.98866271972656},{"x":384.7686462402344,"y":233.32591247558594},{"x":419.96533203125,"y":234.4287109375},{"x":455.4043273925781,"y":235.98060607910156},{"x":245.040771484375,"y":262.8219299316406},{"x":279.5098876953125,"y":264.1510314941406},{"x":313.92010498046875,"y":265.491943359375},{"x":348.6171569824219,"y":266.93072509765625},{"x":383.2054138183594,"y":268.17816162109375},{"x":418.552490234375,"y":269.893310546875},{"x":453.0155029296875,"y":271.1266174316406},{"x":245.32965087890625,"y":296.3208312988281},{"x":279.263916015625,"y":297.9762268066406},{"x":313.22088623046875,"y":299.5179748535156},{"x":347.82318115234375,"y":300.820068359375},{"x":382.0979919433594,"y":302.2673645019531},{"x":416.7114562988281,"y":303.8325500488281},{"x":451.2049255371094,"y":305.44207763671875}],"reprojectionErrors":[{"x":0.012115478515625,"y":0.350250244140625},{"x":-0.187957763671875,"y":0.3769073486328125},{"x":0.09002685546875,"y":-0.11165618896484375},{"x":-0.01226806640625,"y":0.24908447265625},{"x":-0.005584716796875,"y":0.01122283935546875},{"x":-0.135650634765625,"y":-0.130767822265625},{"x":0.1424560546875,"y":0.01811981201171875},{"x":-0.143280029296875,"y":0.30511474609375},{"x":-0.276947021484375,"y":0.08429718017578125},{"x":0.044830322265625,"y":0.3532257080078125},{"x":0.003509521484375,"y":-0.16898345947265625},{"x":0.210174560546875,"y":0.28696441650390625},{"x":-0.044403076171875,"y":0.13384246826171875},{"x":0.321685791015625,"y":0.0379180908203125},{"x":-0.1872406005859375,"y":0.0638275146484375},{"x":0.204193115234375,"y":0.31365966796875},{"x":-0.09912109375,"y":0.107177734375},{"x":-0.1824951171875,"y":-0.0183563232421875},{"x":0.1051025390625,"y":0.03729248046875},{"x":0.059417724609375,"y":-0.1512603759765625},{"x":0.459136962890625,"y":-0.0102081298828125},{"x":-0.5325164794921875,"y":-0.5502471923828125},{"x":-0.236328125,"y":-0.1605987548828125},{"x":-0.181365966796875,"y":0.0272979736328125},{"x":-0.015625,"y":-0.3878173828125},{"x":-0.09613037109375,"y":-0.1577606201171875},{"x":-0.046417236328125,"y":-0.242034912109375},{"x":0.133148193359375,"y":-0.0526275634765625},{"x":-0.22528076171875,"y":0.10601806640625},{"x":-0.14202880859375,"y":0.2041778564453125},{"x":-0.1297607421875,"y":0.1724395751953125},{"x":-0.1904296875,"y":0.091400146484375},{"x":-0.2044677734375,"y":0.109283447265625},{"x":0.013702392578125,"y":0.3612060546875},{"x":0.14361572265625,"y":0.163299560546875},{"x":-0.1395416259765625,"y":-0.23345947265625},{"x":-0.263153076171875,"y":-0.138153076171875},{"x":-0.151824951171875,"y":-0.056304931640625},{"x":-0.157470703125,"y":-0.0743408203125},{"x":0.109283447265625,"y":0.0966796875},{"x":-0.22552490234375,"y":-0.202667236328125},{"x":0.474395751953125,"y":-0.023162841796875},{"x":-0.103607177734375,"y":0.070953369140625},{"x":-0.0731201171875,"y":-0.09368896484375},{"x":0.106903076171875,"y":-0.1484375},{"x":-0.192169189453125,"y":0.03240966796875},{"x":-0.003662109375,"y":0.0635986328125},{"x":-3.0517578125E-5,"y":-0.02783203125},{"x":0.27105712890625,"y":-0.168701171875}],"optimisedCameraToObject":{"translation":{"x":-0.11356671383887333,"y":-0.17429860638544456,"z":0.47012122146438},"rotation":{"quaternion":{"W":0.9934764829645861,"X":0.10966589947086226,"Y":0.025040246152755383,"Z":0.0187311068058632}}},"includeObservationInCalibration":true,"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":367.2918395996094,"y":67.62530517578125},{"x":404.6898498535156,"y":69.92713928222656},{"x":442.1222229003906,"y":72.81950378417969},{"x":479.8296203613281,"y":75.34724426269531},{"x":517.5645751953125,"y":78.1654281616211},{"x":556.0475463867188,"y":80.80663299560547},{"x":594.6295166015625,"y":83.26685333251953},{"x":364.4712219238281,"y":106.00704193115234},{"x":401.33514404296875,"y":109.02845001220703},{"x":438.1849670410156,"y":111.73956298828125},{"x":475.8946228027344,"y":114.54194641113281},{"x":513.2501220703125,"y":117.01956939697266},{"x":551.0753784179688,"y":120.0047378540039},{"x":589.084228515625,"y":122.37987518310547},{"x":361.7715759277344,"y":144.1632537841797},{"x":397.8608093261719,"y":146.83489990234375},{"x":434.76806640625,"y":149.7847900390625},{"x":471.6131591796875,"y":152.58998107910156},{"x":508.7997741699219,"y":155.4178466796875},{"x":546.2542724609375,"y":158.08352661132812},{"x":583.8139038085938,"y":161.015869140625},{"x":359.132568359375,"y":181.45274353027344},{"x":394.9653015136719,"y":184.33155822753906},{"x":431.1470031738281,"y":187.2745819091797},{"x":467.7469177246094,"y":190.042724609375},{"x":504.3866271972656,"y":193.1957550048828},{"x":541.4052124023438,"y":196.06007385253906},{"x":578.7274780273438,"y":198.92942810058594},{"x":356.830322265625,"y":217.109375},{"x":391.8899230957031,"y":219.993896484375},{"x":427.86236572265625,"y":223.025634765625},{"x":464.0811462402344,"y":226.20985412597656},{"x":500.2019958496094,"y":229.1658172607422},{"x":537.0227661132812,"y":232.20359802246094},{"x":573.9921875,"y":235.30296325683594},{"x":354.0520935058594,"y":252.7326202392578},{"x":389.0713195800781,"y":255.83079528808594},{"x":424.4225769042969,"y":258.8902893066406},{"x":460.4226989746094,"y":261.8040466308594},{"x":495.9723815917969,"y":265.1920471191406},{"x":532.4160766601562,"y":268.47662353515625},{"x":568.7553100585938,"y":271.8113098144531},{"x":351.797607421875,"y":287.0257873535156},{"x":386.207763671875,"y":290.1442565917969},{"x":421.3124084472656,"y":293.720947265625},{"x":456.5373229980469,"y":297.0552978515625},{"x":491.90625,"y":300.28033447265625},{"x":528.0879516601562,"y":303.6836853027344},{"x":564.2083129882812,"y":306.9112548828125}],"reprojectionErrors":[{"x":-0.168426513671875,"y":0.04798126220703125},{"x":-0.345947265625,"y":0.32196044921875},{"x":-0.26434326171875,"y":0.03229522705078125},{"x":-0.16961669921875,"y":0.13384246826171875},{"x":0.18023681640625,"y":-0.0287628173828125},{"x":0.05902099609375,"y":0.01155853271484375},{"x":0.1097412109375,"y":0.25849151611328125},{"x":-0.116363525390625,"y":0.27032470703125},{"x":-0.17864990234375,"y":-0.05319976806640625},{"x":0.0604248046875,"y":-0.04186248779296875},{"x":-0.278350830078125,"y":-0.09755706787109375},{"x":0.013671875,"y":0.19538116455078125},{"x":0.10687255859375,"y":0.0042724609375},{"x":0.2816162109375,"y":0.44629669189453125},{"x":-0.122039794921875,"y":-0.1152801513671875},{"x":0.1790771484375,"y":0.0270233154296875},{"x":-0.056640625,"y":-0.086578369140625},{"x":0.04583740234375,"y":-0.033538818359375},{"x":0.077545166015625,"y":0.0183563232421875},{"x":0.1065673828125,"y":0.2535552978515625},{"x":0.28985595703125,"y":0.242767333984375},{"x":-0.126800537109375,"y":-0.4461822509765625},{"x":0.026885986328125,"y":-0.4007110595703125},{"x":0.10693359375,"y":-0.3992919921875},{"x":0.039031982421875,"y":-0.2032623291015625},{"x":0.196319580078125,"y":-0.37286376953125},{"x":0.23431396484375,"y":-0.2349395751953125},{"x":0.22247314453125,"y":-0.0837249755859375},{"x":-0.408355712890625,"y":0.0645294189453125},{"x":0.12176513671875,"y":0.209136962890625},{"x":0.008636474609375,"y":0.2245941162109375},{"x":-0.08624267578125,"y":0.1051177978515625},{"x":0.176300048828125,"y":0.2309722900390625},{"x":-0.00701904296875,"y":0.2915802001953125},{"x":-0.0904541015625,"y":0.3066558837890625},{"x":-0.155517578125,"y":-0.1625213623046875},{"x":0.025299072265625,"y":-0.1319580078125},{"x":0.138092041015625,"y":-0.046722412109375},{"x":-0.13885498046875,"y":0.199737548828125},{"x":0.288665771484375,"y":-0.01312255859375},{"x":0.07098388671875,"y":-0.108154296875},{"x":0.2010498046875,"y":-0.23944091796875},{"x":-0.369476318359375,"y":0.1888427734375},{"x":0.03753662109375,"y":0.293701171875},{"x":0.0086669921875,"y":-0.045684814453125},{"x":0.113311767578125,"y":-0.1292724609375},{"x":0.32275390625,"y":-0.090667724609375},{"x":-0.0369873046875,"y":-0.21807861328125},{"x":-0.09710693359375,"y":-0.157989501953125}],"optimisedCameraToObject":{"translation":{"x":-0.02648596589479527,"y":-0.18232819878905754,"z":0.4625163563911466},"rotation":{"quaternion":{"W":0.9931983687342055,"X":0.1011753142795983,"Y":0.03909697172846946,"Z":0.04233181930653161}}},"includeObservationInCalibration":true,"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":482.02740478515625,"y":67.85414123535156},{"x":519.1791381835938,"y":70.19827270507812},{"x":557.405029296875,"y":73.2572250366211},{"x":596.852783203125,"y":76.17818450927734},{"x":637.25341796875,"y":79.53508758544922},{"x":678.9290161132812,"y":82.88789367675781},{"x":721.172607421875,"y":86.3917236328125},{"x":476.3291015625,"y":105.80760955810547},{"x":513.3225708007812,"y":109.00564575195312},{"x":550.8635864257812,"y":112.14144134521484},{"x":590.0658569335938,"y":115.8410873413086},{"x":629.9588623046875,"y":119.335693359375},{"x":671.113525390625,"y":123.41663360595703},{"x":713.154541015625,"y":127.07598114013672},{"x":471.04571533203125,"y":142.9325714111328},{"x":507.3626403808594,"y":147.03160095214844},{"x":544.5314331054688,"y":150.8074951171875},{"x":583.296142578125,"y":154.7140350341797},{"x":622.63232421875,"y":158.91746520996094},{"x":663.1920776367188,"y":163.245849609375},{"x":704.9970092773438,"y":167.42636108398438},{"x":465.7544860839844,"y":179.81497192382812},{"x":501.59136962890625,"y":184.14988708496094},{"x":538.6113891601562,"y":188.17022705078125},{"x":576.569091796875,"y":193.0123748779297},{"x":615.66650390625,"y":197.40896606445312},{"x":655.939208984375,"y":202.4432830810547},{"x":696.8970336914062,"y":206.7740020751953},{"x":460.8822021484375,"y":215.2262725830078},{"x":496.1688232421875,"y":219.8177947998047},{"x":532.490478515625,"y":224.7072296142578},{"x":570.2700805664062,"y":229.562255859375},{"x":608.61279296875,"y":234.74713134765625},{"x":648.3853759765625,"y":239.83773803710938},{"x":689.23779296875,"y":245.4080810546875},{"x":455.7551574707031,"y":250.49452209472656},{"x":491.04547119140625,"y":255.74461364746094},{"x":526.4088134765625,"y":260.80694580078125},{"x":563.9888916015625,"y":266.3124694824219},{"x":601.850341796875,"y":271.900390625},{"x":641.2565307617188,"y":277.5727844238281},{"x":681.3260498046875,"y":283.3553771972656},{"x":450.9871520996094,"y":284.8897705078125},{"x":485.68463134765625,"y":290.39886474609375},{"x":521.0753784179688,"y":296.0263366699219},{"x":557.8743896484375,"y":301.7718811035156},{"x":595.37109375,"y":307.8623962402344},{"x":634.2429809570312,"y":313.9140319824219},{"x":673.9807739257812,"y":320.4443359375}],"reprojectionErrors":[{"x":-0.491119384765625,"y":-0.38817596435546875},{"x":-0.38067626953125,"y":0.161895751953125},{"x":-0.2926025390625,"y":0.087646484375},{"x":-0.33868408203125,"y":0.24506378173828125},{"x":-0.2122802734375,"y":0.06351470947265625},{"x":-0.19622802734375,"y":-0.01349639892578125},{"x":0.45733642578125,"y":-0.13748931884765625},{"x":-0.14837646484375,"y":-0.33753204345703125},{"x":-0.32159423828125,"y":-0.1468048095703125},{"x":-0.0130615234375,"y":0.206634521484375},{"x":-0.30157470703125,"y":0.10013580322265625},{"x":-0.180419921875,"y":0.306182861328125},{"x":-0.1826171875,"y":0.03714752197265625},{"x":0.106689453125,"y":0.30487823486328125},{"x":-0.112518310546875,"y":-0.1899566650390625},{"x":-0.042755126953125,"y":-0.425506591796875},{"x":0.18267822265625,"y":-0.2281646728515625},{"x":-0.1466064453125,"y":-0.04803466796875},{"x":0.0289306640625,"y":-0.047515869140625},{"x":0.09368896484375,"y":-0.0506744384765625},{"x":0.0643310546875,"y":0.219512939453125},{"x":0.036773681640625,"y":-0.515472412109375},{"x":0.161224365234375,"y":-0.5312652587890625},{"x":0.0888671875,"y":-0.1141204833984375},{"x":0.0977783203125,"y":-0.3965301513671875},{"x":0.01971435546875,"y":-0.1070404052734375},{"x":-0.1455078125,"y":-0.32470703125},{"x":0.12908935546875,"y":0.29620361328125},{"x":-0.12957763671875,"y":-0.0699615478515625},{"x":0.12774658203125,"y":0.0948486328125},{"x":0.3157958984375,"y":0.0881195068359375},{"x":0.0430908203125,"y":0.246246337890625},{"x":0.2373046875,"y":0.2092437744140625},{"x":0.065673828125,"y":0.4056549072265625},{"x":-0.08612060546875,"y":0.26611328125},{"x":0.059844970703125,"y":-0.1663665771484375},{"x":-0.096099853515625,"y":-0.240631103515625},{"x":0.62060546875,"y":0.006622314453125},{"x":0.09674072265625,"y":-0.05126953125},{"x":0.29925537109375,"y":-0.049102783203125},{"x":-0.002197265625,"y":0.01568603515625},{"x":0.10809326171875,"y":0.122161865234375},{"x":-0.010955810546875,"y":-0.059967041015625},{"x":0.02392578125,"y":0.0091552734375},{"x":0.29168701171875,"y":0.10052490234375},{"x":0.10687255859375,"y":0.2188720703125},{"x":0.2105712890625,"y":0.141876220703125},{"x":-0.04278564453125,"y":0.25811767578125},{"x":-0.11083984375,"y":0.0550537109375}],"optimisedCameraToObject":{"translation":{"x":0.054151361053929314,"y":-0.1858468240620645,"z":0.4725195135072814},"rotation":{"quaternion":{"W":0.9849507004338287,"X":0.08391289301021776,"Y":0.13360726023493064,"Z":0.07056801055776961}}},"includeObservationInCalibration":true,"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":519.5244140625,"y":245.12351989746094},{"x":558.471923828125,"y":251.675048828125},{"x":596.7239990234375,"y":257.7232360839844},{"x":635.6854858398438,"y":263.98468017578125},{"x":674.5379028320312,"y":270.32366943359375},{"x":713.6610717773438,"y":276.7524108886719},{"x":752.1699829101562,"y":283.218505859375},{"x":512.980224609375,"y":283.0467529296875},{"x":551.4111938476562,"y":289.54351806640625},{"x":589.6847534179688,"y":295.5984191894531},{"x":628.8233032226562,"y":302.40472412109375},{"x":667.6785278320312,"y":308.7755432128906},{"x":706.1992797851562,"y":315.4500427246094},{"x":744.8543090820312,"y":321.6322937011719},{"x":505.95404052734375,"y":321.15545654296875},{"x":544.0733642578125,"y":327.5103454589844},{"x":582.5726318359375,"y":333.92938232421875},{"x":621.123779296875,"y":340.270751953125},{"x":659.8519897460938,"y":346.8523254394531},{"x":698.9984130859375,"y":353.3747863769531},{"x":737.465576171875,"y":360.04595947265625},{"x":499.17425537109375,"y":358.8080139160156},{"x":537.33056640625,"y":365.2261962890625},{"x":575.4298706054688,"y":371.4945373535156},{"x":614.0624389648438,"y":378.6170654296875},{"x":652.7932739257812,"y":385.22918701171875},{"x":691.76416015625,"y":391.7854309082031},{"x":730.0270385742188,"y":398.1099853515625},{"x":492.56658935546875,"y":395.71905517578125},{"x":530.6734008789062,"y":402.3073425292969},{"x":568.4944458007812,"y":409.10186767578125},{"x":607.2514038085938,"y":415.79791259765625},{"x":645.548095703125,"y":422.4119567871094},{"x":684.2268676757812,"y":428.8694152832031},{"x":723.0330810546875,"y":435.78070068359375},{"x":485.85308837890625,"y":433.1748962402344},{"x":523.7552490234375,"y":440.01055908203125},{"x":561.7548217773438,"y":446.6956481933594},{"x":600.1557006835938,"y":453.33441162109375},{"x":638.3101196289062,"y":460.0498352050781},{"x":677.0709228515625,"y":467.0345153808594},{"x":715.3709106445312,"y":473.7884521484375},{"x":479.2823181152344,"y":469.9844970703125},{"x":517.0146484375,"y":476.75030517578125},{"x":555.22998046875,"y":483.81219482421875},{"x":593.109130859375,"y":490.187744140625},{"x":631.504150390625,"y":497.5484619140625},{"x":669.8975219726562,"y":504.2423095703125},{"x":708.2178955078125,"y":511.0511474609375}],"reprojectionErrors":[{"x":0.11614990234375,"y":-0.254241943359375},{"x":-0.3385009765625,"y":-0.45989990234375},{"x":0.067626953125,"y":-0.13177490234375},{"x":-0.07867431640625,"y":0.01220703125},{"x":0.03265380859375,"y":0.1063232421875},{"x":0.01312255859375,"y":0.136993408203125},{"x":0.73895263671875,"y":0.155181884765625},{"x":-0.10357666015625,"y":-0.041595458984375},{"x":-0.16766357421875,"y":-0.121429443359375},{"x":0.09051513671875,"y":0.2681884765625},{"x":-0.3597412109375,"y":-0.067413330078125},{"x":-0.37847900390625,"y":0.0572509765625},{"x":0.07672119140625,"y":-0.098419189453125},{"x":0.528564453125,"y":0.260040283203125},{"x":0.191925048828125,"y":-0.23443603515625},{"x":0.31231689453125,"y":-0.102569580078125},{"x":0.2171630859375,"y":-0.0101318359375},{"x":0.2261962890625,"y":0.18328857421875},{"x":0.2059326171875,"y":0.158416748046875},{"x":-0.0933837890625,"y":0.21307373046875},{"x":0.4171142578125,"y":0.137969970703125},{"x":0.274993896484375,"y":-0.195037841796875},{"x":0.2301025390625,"y":-0.057952880859375},{"x":0.40606689453125,"y":0.25091552734375},{"x":0.20440673828125,"y":-0.27392578125},{"x":0.05181884765625,"y":-0.269317626953125},{"x":-0.2020263671875,"y":-0.191314697265625},{"x":0.38238525390625,"y":0.1343994140625},{"x":0.22064208984375,"y":0.358062744140625},{"x":0.09588623046875,"y":0.392333984375},{"x":0.420166015625,"y":0.239501953125},{"x":-0.03631591796875,"y":0.20281982421875},{"x":0.11431884765625,"y":0.26434326171875},{"x":0.0213623046875,"y":0.49713134765625},{"x":-0.069091796875,"y":0.2891845703125},{"x":0.307586669921875,"y":0.134918212890625},{"x":0.2569580078125,"y":-0.012237548828125},{"x":0.27166748046875,"y":0.007598876953125},{"x":0.03973388671875,"y":0.08868408203125},{"x":0.20068359375,"y":0.106475830078125},{"x":-0.106689453125,"y":-0.133148193359375},{"x":0.1763916015625,"y":-0.13177490234375},{"x":0.28790283203125,"y":0.3228759765625},{"x":0.27557373046875,"y":0.310302734375},{"x":-0.0576171875,"y":0.01531982421875},{"x":0.09954833984375,"y":0.4188232421875},{"x":-0.1131591796875,"y":-0.1522216796875},{"x":-0.18658447265625,"y":-0.04736328125},{"x":-0.0577392578125,"y":-0.050048828125}],"optimisedCameraToObject":{"translation":{"x":0.07634276098870524,"y":-0.06291076841626946,"z":0.45015164748900965},"rotation":{"quaternion":{"W":0.9960034574789867,"X":0.024613647352990743,"Y":0.021443639868140046,"Z":0.08313513915963891}}},"includeObservationInCalibration":true,"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":130.29617309570312,"y":249.16114807128906},{"x":163.83306884765625,"y":252.67201232910156},{"x":198.07093811035156,"y":256.255126953125},{"x":233.09371948242188,"y":260.1888122558594},{"x":268.87518310546875,"y":264.0448303222656},{"x":305.1092834472656,"y":267.8274841308594},{"x":341.9736022949219,"y":271.7432556152344},{"x":129.827880859375,"y":285.33660888671875},{"x":163.10235595703125,"y":289.0769348144531},{"x":196.822265625,"y":293.134765625},{"x":231.08750915527344,"y":297.2909851074219},{"x":266.2427062988281,"y":300.921630859375},{"x":302.7452392578125,"y":305.586669921875},{"x":339.181640625,"y":309.7203674316406},{"x":129.23135375976562,"y":320.7911071777344},{"x":162.02432250976562,"y":324.95709228515625},{"x":195.8250274658203,"y":328.9322204589844},{"x":229.88400268554688,"y":333.31048583984375},{"x":264.8960876464844,"y":337.78515625},{"x":300.0954895019531,"y":342.4007568359375},{"x":336.4063415527344,"y":346.95745849609375},{"x":128.90687561035156,"y":355.5209655761719},{"x":161.13555908203125,"y":360.02227783203125},{"x":194.13937377929688,"y":364.622802734375},{"x":228.11398315429688,"y":369.44232177734375},{"x":262.816650390625,"y":374.0978088378906},{"x":297.74072265625,"y":379.30499267578125},{"x":333.7509765625,"y":383.5601501464844},{"x":128.35232543945312,"y":389.3068542480469},{"x":160.23255920410156,"y":394.2916259765625},{"x":193.2902069091797,"y":398.9712829589844},{"x":226.87437438964844,"y":404.19024658203125},{"x":260.82757568359375,"y":409.2768859863281},{"x":295.972412109375,"y":414.0907897949219},{"x":331.1429443359375,"y":419.7847900390625},{"x":127.55606842041016,"y":423.3240051269531},{"x":159.58749389648438,"y":428.47296142578125},{"x":192.0301055908203,"y":433.5769958496094},{"x":225.45359802246094,"y":438.7577209472656},{"x":258.9909362792969,"y":444.1112060546875},{"x":293.7815246582031,"y":449.9676818847656},{"x":328.56982421875,"y":455.7482604980469},{"x":127.20055389404297,"y":456.12188720703125},{"x":158.61007690429688,"y":461.47711181640625},{"x":190.50961303710938,"y":467.2626647949219},{"x":223.7522430419922,"y":472.83428955078125},{"x":257.1024169921875,"y":478.5074768066406},{"x":291.06451416015625,"y":483.9815368652344},{"x":326.1264343261719,"y":490.3427429199219}],"reprojectionErrors":[{"x":0.30828857421875,"y":0.2195892333984375},{"x":0.065460205078125,"y":0.2335205078125},{"x":-0.1358795166015625,"y":0.246429443359375},{"x":-0.363372802734375,"y":-0.0185546875},{"x":-0.574127197265625,"y":-0.13165283203125},{"x":-0.445068359375,"y":-0.0955810546875},{"x":-0.13641357421875,"y":-0.11529541015625},{"x":0.064056396484375,"y":0.0189208984375},{"x":-0.2126922607421875,"y":0.15325927734375},{"x":-0.2051544189453125,"y":0.045440673828125},{"x":0.0025634765625,"y":-0.083953857421875},{"x":0.08203125,"y":0.390655517578125},{"x":-0.40765380859375,"y":-0.089111328125},{"x":-0.036163330078125,"y":0.044036865234375},{"x":-0.02154541015625,"y":-0.0791015625},{"x":-0.1092681884765625,"y":-0.033203125},{"x":-0.4874725341796875,"y":0.28265380859375},{"x":-0.391387939453125,"y":0.27606201171875},{"x":-0.5001220703125,"y":0.25537109375},{"x":-0.031951904296875,"y":0.1776123046875},{"x":0.1053466796875,"y":0.24432373046875},{"x":-0.349517822265625,"y":-0.059906005859375},{"x":-0.161590576171875,"y":-0.02447509765625},{"x":-0.043792724609375,"y":-0.005615234375},{"x":-0.1768951416015625,"y":-0.121490478515625},{"x":-0.30291748046875,"y":0.01251220703125},{"x":0.100250244140625,"y":-0.317657470703125},{"x":0.1837158203125,"y":0.393341064453125},{"x":-0.418365478515625,"y":0.306427001953125},{"x":-0.1669158935546875,"y":0.171356201171875},{"x":-0.3998260498046875,"y":0.42730712890625},{"x":-0.451751708984375,"y":0.231475830078125},{"x":-0.15045166015625,"y":0.257110595703125},{"x":-0.30352783203125,"y":0.64630126953125},{"x":0.270355224609375,"y":0.247894287109375},{"x":-0.2171173095703125,"y":-0.1448974609375},{"x":-0.3980865478515625,"y":-0.14276123046875},{"x":-0.3089141845703125,"y":-0.00677490234375},{"x":-0.5052642822265625,"y":0.143035888671875},{"x":-0.10577392578125,"y":0.212310791015625},{"x":-0.235321044921875,"y":-0.127593994140625},{"x":0.376556396484375,"y":-0.29608154296875},{"x":-0.428863525390625,"y":0.04693603515625},{"x":-0.2655487060546875,"y":0.13299560546875},{"x":0.0776214599609375,"y":-0.11956787109375},{"x":-0.2388458251953125,"y":-0.06494140625},{"x":0.034515380859375,"y":-0.016876220703125},{"x":0.40740966796875,"y":0.326904296875},{"x":0.40643310546875,"y":-0.11810302734375}],"optimisedCameraToObject":{"translation":{"x":-0.19093928670759655,"y":-0.06030370969747975,"z":0.47843488448395616},"rotation":{"quaternion":{"W":0.9905543918397711,"X":0.07821383582808601,"Y":0.10244881080613036,"Z":0.046784974686410845}}},"includeObservationInCalibration":true,"snapshotName":"img12.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":190.16746520996094,"y":143.6483612060547},{"x":232.9264373779297,"y":146.91757202148438},{"x":274.3643798828125,"y":150.08258056640625},{"x":314.30096435546875,"y":153.482177734375},{"x":352.54217529296875,"y":156.5852508544922},{"x":390.0780944824219,"y":159.57150268554688},{"x":425.94189453125,"y":162.14874267578125},{"x":189.255126953125,"y":185.86090087890625},{"x":232.15676879882812,"y":188.27972412109375},{"x":272.73980712890625,"y":190.87521362304688},{"x":312.7359313964844,"y":193.68670654296875},{"x":351.0829162597656,"y":196.02769470214844},{"x":388.3519287109375,"y":198.09368896484375},{"x":423.9833984375,"y":200.28611755371094},{"x":188.35340881347656,"y":227.68710327148438},{"x":230.62713623046875,"y":229.65335083007812},{"x":271.5768737792969,"y":231.12295532226562},{"x":311.01300048828125,"y":233.15292358398438},{"x":349.0953063964844,"y":235.00526428222656},{"x":386.16455078125,"y":236.61349487304688},{"x":421.8720397949219,"y":238.08103942871094},{"x":187.4383087158203,"y":269.0171813964844},{"x":229.74769592285156,"y":270.00946044921875},{"x":269.96893310546875,"y":271.0544738769531},{"x":309.5205993652344,"y":272.68438720703125},{"x":347.4969177246094,"y":273.46392822265625},{"x":384.5373840332031,"y":274.8607177734375},{"x":419.8016357421875,"y":275.8512268066406},{"x":186.5628204345703,"y":309.2423095703125},{"x":228.2252655029297,"y":309.78009033203125},{"x":268.69036865234375,"y":310.25726318359375},{"x":307.8885803222656,"y":310.7570495605469},{"x":345.8280029296875,"y":311.1353759765625},{"x":382.39013671875,"y":311.9581298828125},{"x":418.0929260253906,"y":312.3589172363281},{"x":185.26693725585938,"y":349.5543518066406},{"x":227.11549377441406,"y":349.55419921875},{"x":266.98382568359375,"y":349.2853088378906},{"x":306.2809753417969,"y":349.4573974609375},{"x":343.7716064453125,"y":349.3941650390625},{"x":380.6850891113281,"y":349.2898864746094},{"x":415.9270324707031,"y":349.35089111328125},{"x":184.5811004638672,"y":389.0827331542969},{"x":225.88528442382812,"y":388.6552734375},{"x":266.0425720214844,"y":387.9825439453125},{"x":304.8479919433594,"y":387.1640930175781},{"x":342.18994140625,"y":386.4454040527344},{"x":378.5357971191406,"y":385.92352294921875},{"x":413.9472961425781,"y":385.5028991699219}],"reprojectionErrors":[{"x":0.408355712890625,"y":-0.083587646484375},{"x":0.14666748046875,"y":-0.0677337646484375},{"x":-0.136199951171875,"y":-0.045440673828125},{"x":-0.207275390625,"y":-0.3517303466796875},{"x":0.177520751953125,"y":-0.4518585205078125},{"x":0.07568359375,"y":-0.522125244140625},{"x":0.499359130859375,"y":-0.2670745849609375},{"x":0.388580322265625,"y":-0.07440185546875},{"x":-0.2545623779296875,"y":0.102630615234375},{"x":0.094146728515625,"y":0.024017333984375},{"x":-0.245330810546875,"y":-0.346527099609375},{"x":-0.16156005859375,"y":-0.319580078125},{"x":-0.178985595703125,"y":-0.0879058837890625},{"x":0.30645751953125,"y":-0.0502777099609375},{"x":0.3690948486328125,"y":-0.1883392333984375},{"x":0.11553955078125,"y":-0.2318267822265625},{"x":-0.125457763671875,"y":0.1604461669921875},{"x":-0.113525390625,"y":-0.0661468505859375},{"x":0.039764404296875,"y":-0.17138671875},{"x":0.03961181640625,"y":-0.0866546630859375},{"x":0.2784423828125,"y":0.086669921875},{"x":0.3738250732421875,"y":-0.313018798828125},{"x":-0.1532135009765625,"y":-0.03973388671875},{"x":0.111663818359375,"y":0.137359619140625},{"x":-0.200347900390625,"y":-0.312164306640625},{"x":-0.13604736328125,"y":0.048553466796875},{"x":-0.28985595703125,"y":-0.24652099609375},{"x":0.221588134765625,"y":-0.172454833984375},{"x":0.3497467041015625,"y":0.163177490234375},{"x":0.2323455810546875,"y":0.249359130859375},{"x":0.031097412109375,"y":0.36956787109375},{"x":-0.13555908203125,"y":0.441558837890625},{"x":-0.22918701171875,"y":0.610504150390625},{"x":-0.087005615234375,"y":0.311431884765625},{"x":-0.184722900390625,"y":0.411712646484375},{"x":0.7567901611328125,"y":0.05108642578125},{"x":0.216522216796875,"y":0.049102783203125},{"x":0.390228271484375,"y":0.305419921875},{"x":-0.083160400390625,"y":0.110748291015625},{"x":0.077362060546875,"y":0.141845703125},{"x":-0.314056396484375,"y":0.204925537109375},{"x":-0.121551513671875,"y":0.093994140625},{"x":0.564483642578125,"y":0.224273681640625},{"x":0.3323974609375,"y":0.038665771484375},{"x":-0.004241943359375,"y":0.10345458984375},{"x":-0.193389892578125,"y":0.318939208984375},{"x":-0.078582763671875,"y":0.439605712890625},{"x":-0.084503173828125,"y":0.3682861328125},{"x":-0.232086181640625,"y":0.200469970703125}],"optimisedCameraToObject":{"translation":{"x":-0.13350220864243958,"y":-0.11844978960616115,"z":0.40735206253438333},"rotation":{"quaternion":{"W":0.9892457239984286,"X":0.05386148376378119,"Y":-0.13483600756999845,"Z":0.01763772037911974}}},"includeObservationInCalibration":true,"snapshotName":"img13.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":135.70372009277344,"y":130.54415893554688},{"x":171.04296875,"y":133.48390197753906},{"x":204.86813354492188,"y":136.50344848632812},{"x":236.7733917236328,"y":139.4121551513672},{"x":267.80328369140625,"y":142.12548828125},{"x":297.23724365234375,"y":145.0078582763672},{"x":325.42840576171875,"y":147.2733154296875},{"x":135.77622985839844,"y":164.85025024414062},{"x":170.9188690185547,"y":167.14198303222656},{"x":204.05380249023438,"y":169.6541290283203},{"x":236.2957000732422,"y":171.9164276123047},{"x":266.98126220703125,"y":173.62393188476562},{"x":296.63201904296875,"y":175.88377380371094},{"x":324.6925048828125,"y":177.76669311523438},{"x":135.8569793701172,"y":199.04226684570312},{"x":170.4993438720703,"y":200.33941650390625},{"x":203.87008666992188,"y":201.97802734375},{"x":235.69801330566406,"y":203.43576049804688},{"x":266.0592956542969,"y":205.0555419921875},{"x":295.6465148925781,"y":206.41632080078125},{"x":323.4291076660156,"y":207.39642333984375},{"x":135.67372131347656,"y":232.6307830810547},{"x":170.05120849609375,"y":233.51934814453125},{"x":203.15731811523438,"y":234.11045837402344},{"x":235.13768005371094,"y":234.9561004638672},{"x":265.3049621582031,"y":235.984375},{"x":294.562255859375,"y":236.436767578125},{"x":322.2104797363281,"y":237.13143920898438},{"x":135.68780517578125,"y":265.1072082519531},{"x":169.90780639648438,"y":265.2215270996094},{"x":202.70770263671875,"y":265.6954650878906},{"x":234.25071716308594,"y":265.9800720214844},{"x":264.36181640625,"y":266.0235290527344},{"x":291.53448486328125,"y":265.2059631347656},{"x":321.4366149902344,"y":266.0709533691406},{"x":135.32705688476562,"y":298.01507568359375},{"x":169.63197326660156,"y":297.583740234375},{"x":202.10183715820312,"y":297.10906982421875},{"x":233.39935302734375,"y":296.8614807128906},{"x":263.5686950683594,"y":296.10162353515625},{"x":292.72344970703125,"y":295.94256591796875},{"x":320.4378662109375,"y":295.2640380859375},{"x":135.24295043945312,"y":330.0309753417969},{"x":169.0897216796875,"y":329.0679016113281},{"x":201.6971435546875,"y":328.0373229980469},{"x":232.90109252929688,"y":326.9543762207031},{"x":262.87213134765625,"y":325.78521728515625},{"x":291.6903381347656,"y":324.8067321777344},{"x":319.0472412109375,"y":324.0692138671875}],"reprojectionErrors":[{"x":0.6999969482421875,"y":0.1876068115234375},{"x":0.1791534423828125,"y":0.187469482421875},{"x":-0.2088775634765625,"y":-0.00518798828125},{"x":0.016021728515625,"y":-0.193695068359375},{"x":-0.12158203125,"y":-0.2878875732421875},{"x":0.16314697265625,"y":-0.6469573974609375},{"x":0.577117919921875,"y":-0.48004150390625},{"x":0.544830322265625,"y":0.2069549560546875},{"x":4.57763671875E-4,"y":0.1505889892578125},{"x":0.099822998046875,"y":-0.212646484375},{"x":-0.19891357421875,"y":-0.4078826904296875},{"x":-0.16461181640625,"y":-0.1258544921875},{"x":-0.25567626953125,"y":-0.4697265625},{"x":0.142333984375,"y":-0.5064849853515625},{"x":0.37921142578125,"y":-0.1033935546875},{"x":0.116455078125,"y":0.148223876953125},{"x":-0.2216033935546875,"y":-0.002777099609375},{"x":-0.29229736328125,"y":-0.030792236328125},{"x":-0.105255126953125,"y":-0.2757568359375},{"x":-0.291046142578125,"y":-0.31378173828125},{"x":0.23883056640625,"y":-0.02056884765625},{"x":0.4754180908203125,"y":-0.24951171875},{"x":0.2603607177734375,"y":-0.258575439453125},{"x":-0.0134124755859375,"y":-0.0070037841796875},{"x":-0.421417236328125,"y":-0.0448455810546875},{"x":-0.21099853515625,"y":-0.2983551025390625},{"x":-0.224365234375,"y":-0.007354736328125},{"x":0.29443359375,"y":0.0116119384765625},{"x":0.3721771240234375,"y":0.28173828125},{"x":0.098876953125,"y":0.394622802734375},{"x":-0.067779541015625,"y":0.134490966796875},{"x":-0.2222442626953125,"y":0.05096435546875},{"x":-0.125396728515625,"y":0.19659423828125},{"x":1.789093017578125,"y":1.19183349609375},{"x":-0.0908203125,"y":0.49371337890625},{"x":0.641693115234375,"y":-0.0487060546875},{"x":0.0692291259765625,"y":-0.02581787109375},{"x":0.034759521484375,"y":0.04949951171875},{"x":-0.0569610595703125,"y":-0.0936279296875},{"x":-0.18719482421875,"y":0.283721923828125},{"x":-0.410797119140625,"y":0.068145751953125},{"x":-0.2471923828125,"y":0.3795166015625},{"x":0.632568359375,"y":0.087066650390625},{"x":0.3054351806640625,"y":0.022369384765625},{"x":-0.0631866455078125,"y":0.055877685546875},{"x":-0.2430267333984375,"y":0.1708984375},{"x":-0.3428955078125,"y":0.399871826171875},{"x":-0.385223388671875,"y":0.46453857421875},{"x":-0.00762939453125,"y":0.3133544921875}],"optimisedCameraToObject":{"translation":{"x":-0.19899474827153943,"y":-0.14911436496015743,"z":0.5013172545504098},"rotation":{"quaternion":{"W":0.9741621681960915,"X":0.07103489358595931,"Y":-0.21417932030088419,"Z":0.009451597969270916}}},"includeObservationInCalibration":true,"snapshotName":"img14.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":145.9443817138672,"y":304.1503601074219},{"x":186.30406188964844,"y":306.0598449707031},{"x":225.12879943847656,"y":307.8197021484375},{"x":264.03631591796875,"y":309.304931640625},{"x":301.690185546875,"y":311.07177734375},{"x":339.0354309082031,"y":312.703369140625},{"x":375.21649169921875,"y":314.0296630859375},{"x":145.766845703125,"y":340.86181640625},{"x":185.43724060058594,"y":342.3179626464844},{"x":223.99205017089844,"y":343.4752502441406},{"x":262.1709899902344,"y":345.4200439453125},{"x":299.7766418457031,"y":346.61285400390625},{"x":336.4263916015625,"y":347.7964172363281},{"x":371.9783935546875,"y":348.98626708984375},{"x":145.46630859375,"y":376.8085632324219},{"x":184.12835693359375,"y":377.4175720214844},{"x":222.9355010986328,"y":378.9134216308594},{"x":260.31829833984375,"y":379.8584899902344},{"x":297.1507263183594,"y":380.88885498046875},{"x":333.5131530761719,"y":382.0174560546875},{"x":368.8775939941406,"y":383.1126403808594},{"x":145.17442321777344,"y":411.5334777832031},{"x":183.7990264892578,"y":412.43768310546875},{"x":221.43624877929688,"y":413.2135009765625},{"x":258.7510070800781,"y":413.92462158203125},{"x":294.6881408691406,"y":414.283447265625},{"x":330.9254150390625,"y":415.66522216796875},{"x":366.0765075683594,"y":416.2132873535156},{"x":145.04808044433594,"y":445.2568359375},{"x":182.96188354492188,"y":445.8124084472656},{"x":220.13418579101562,"y":446.3155212402344},{"x":257.0215759277344,"y":446.68756103515625},{"x":293.0394592285156,"y":447.15338134765625},{"x":328.2884826660156,"y":447.6198425292969},{"x":363.2686462402344,"y":448.06353759765625},{"x":144.3304443359375,"y":478.4935607910156},{"x":182.11508178710938,"y":478.9269714355469},{"x":218.7119903564453,"y":479.105224609375},{"x":255.25474548339844,"y":479.22821044921875},{"x":290.97125244140625,"y":479.6271667480469},{"x":325.8437805175781,"y":480.07696533203125},{"x":360.1378173828125,"y":480.35833740234375},{"x":144.4270782470703,"y":510.79913330078125},{"x":181.16558837890625,"y":510.7248229980469},{"x":217.770263671875,"y":511.0228271484375},{"x":253.59451293945312,"y":510.9925231933594},{"x":288.8172607421875,"y":511.0450744628906},{"x":323.54339599609375,"y":510.8504943847656},{"x":357.57879638671875,"y":511.0558776855469}],"reprojectionErrors":[{"x":0.0764617919921875,"y":-0.255523681640625},{"x":-0.305877685546875,"y":-0.317657470703125},{"x":0.148162841796875,"y":-0.277587890625},{"x":-0.169677734375,"y":-0.009521484375},{"x":0.086456298828125,"y":-0.06884765625},{"x":-0.019073486328125,"y":-0.03790283203125},{"x":0.378631591796875,"y":0.25421142578125},{"x":-0.0164794921875,"y":-0.03033447265625},{"x":-0.249847412109375,"y":0.01312255859375},{"x":-0.047332763671875,"y":0.311859130859375},{"x":-0.139678955078125,"y":-0.2196044921875},{"x":-0.320556640625,"y":-0.041015625},{"x":-0.19842529296875,"y":0.10565185546875},{"x":0.37744140625,"y":0.205657958984375},{"x":0.0269317626953125,"y":-0.051300048828125},{"x":0.2740631103515625,"y":0.50946044921875},{"x":-0.2854156494140625,"y":0.1434326171875},{"x":-0.073577880859375,"y":0.289031982421875},{"x":0.0440673828125,"y":0.310882568359375},{"x":-0.004425048828125,"y":0.196868896484375},{"x":0.31744384765625,"y":0.079345703125},{"x":0.0745391845703125,"y":0.174102783203125},{"x":-0.1566619873046875,"y":0.126861572265625},{"x":-0.044464111328125,"y":0.17132568359375},{"x":-0.245758056640625,"y":0.24456787109375},{"x":0.302642822265625,"y":0.634918212890625},{"x":-0.06903076171875,"y":-0.03216552734375},{"x":0.03363037109375,"y":0.10076904296875},{"x":-0.031036376953125,"y":0.4593505859375},{"x":-0.0555419921875,"y":0.464019775390625},{"x":0.0343780517578125,"y":0.48748779296875},{"x":-0.210296630859375,"y":0.609039306640625},{"x":-0.197296142578125,"y":0.604583740234375},{"x":-0.01971435546875,"y":0.567962646484375},{"x":-0.169891357421875,"y":0.52325439453125},{"x":0.4665985107421875,"y":0.32183837890625},{"x":0.0784454345703125,"y":0.167205810546875},{"x":0.267242431640625,"y":0.23675537109375},{"x":-0.093414306640625,"y":0.331329345703125},{"x":-0.224151611328125,"y":0.120391845703125},{"x":-0.10003662109375,"y":-0.17022705078125},{"x":0.02069091796875,"y":-0.32061767578125},{"x":0.1614532470703125,"y":0.236968994140625},{"x":0.3375244140625,"y":0.322998046875},{"x":0.0523834228515625,"y":0.008270263671875},{"x":-0.0405731201171875,"y":-0.005950927734375},{"x":-0.113372802734375,"y":-0.130126953125},{"x":-0.26409912109375,"y":-0.0335693359375},{"x":-0.291656494140625,"y":-0.36273193359375}],"optimisedCameraToObject":{"translation":{"x":-0.17046697055025048,"y":-0.020720616241335747,"z":0.4376303191485832},"rotation":{"quaternion":{"W":0.988276934138473,"X":0.12741949596490243,"Y":-0.07662921800871669,"Z":0.0346545299388587}}},"includeObservationInCalibration":true,"snapshotName":"img15.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img15.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.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.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":238.13990783691406,"y":137.11822509765625},{"x":275.8232116699219,"y":140.14871215820312},{"x":313.0944519042969,"y":143.5035858154297},{"x":349.5731506347656,"y":146.15182495117188},{"x":385.9819641113281,"y":149.22865295410156},{"x":198.546875,"y":172.1566925048828},{"x":310.92333984375,"y":180.662353515625},{"x":347.7194519042969,"y":183.1135711669922},{"x":383.3493957519531,"y":185.72036743164062},{"x":158.65052795410156,"y":206.96470642089844},{"x":196.72593688964844,"y":209.5020751953125},{"x":345.0337829589844,"y":219.84605407714844},{"x":380.94268798828125,"y":222.14138793945312},{"x":157.2664031982422,"y":244.6553192138672},{"x":195.4091033935547,"y":246.92889404296875},{"x":232.61843872070312,"y":249.07127380371094},{"x":343.0581970214844,"y":255.92236328125},{"x":378.44793701171875,"y":258.24664306640625},{"x":155.88987731933594,"y":281.3567199707031},{"x":193.85877990722656,"y":283.3215026855469},{"x":230.8083038330078,"y":285.7000732421875},{"x":268.09149169921875,"y":287.6693420410156},{"x":304.64190673828125,"y":289.7224426269531},{"x":340.5041198730469,"y":291.5997619628906},{"x":376.1053771972656,"y":293.8971252441406},{"x":154.47230529785156,"y":318.2977600097656},{"x":192.2004852294922,"y":320.0201416015625},{"x":229.2196807861328,"y":321.9282531738281},{"x":266.19097900390625,"y":323.9358215332031},{"x":302.3787536621094,"y":325.3965759277344},{"x":338.40753173828125,"y":327.6666564941406},{"x":190.65594482421875,"y":356.0038757324219},{"x":227.5541534423828,"y":357.852783203125},{"x":264.1708679199219,"y":359.1638488769531},{"x":300.3353271484375,"y":361.03277587890625},{"x":336.1874694824219,"y":362.30023193359375}],"reprojectionErrors":[{"x":0.0576171875,"y":-0.137176513671875},{"x":0.024505615234375,"y":-0.07781982421875},{"x":-0.08294677734375,"y":-0.37640380859375},{"x":0.11663818359375,"y":-0.001922607421875},{"x":-0.098175048828125,"y":-0.0896759033203125},{"x":-0.1067352294921875,"y":-0.2735748291015625},{"x":-0.0682373046875,"y":-0.2872161865234375},{"x":-0.3551025390625,"y":0.026458740234375},{"x":0.044647216796875,"y":0.15167236328125},{"x":-0.056610107421875,"y":-0.0841827392578125},{"x":0.115509033203125,"y":0.0195465087890625},{"x":0.02569580078125,"y":-0.0831451416015625},{"x":-0.01800537109375,"y":0.1012725830078125},{"x":-0.0610504150390625,"y":-0.2724456787109375},{"x":-0.1451568603515625,"y":-0.1552886962890625},{"x":0.231292724609375,"y":0.0612335205078125},{"x":-0.282958984375,"y":0.096405029296875},{"x":0.02783203125,"y":0.00439453125},{"x":-0.05194091796875,"y":0.137542724609375},{"x":-0.1512451171875,"y":0.318084716796875},{"x":0.30096435546875,"y":0.053436279296875},{"x":-0.048004150390625,"y":0.166778564453125},{"x":-0.131195068359375,"y":0.165130615234375},{"x":0.007537841796875,"y":0.308197021484375},{"x":-0.05810546875,"y":3.662109375E-4},{"x":0.0192108154296875,"y":-0.0823974609375},{"x":-0.0283660888671875,"y":0.100006103515625},{"x":0.170074462890625,"y":0.065643310546875},{"x":-0.0462646484375,"y":-0.098968505859375},{"x":0.0587158203125,"y":0.252532958984375},{"x":-0.138824462890625,"y":-0.23577880859375},{"x":0.0016632080078125,"y":0.212066650390625},{"x":0.1369781494140625,"y":0.0015869140625},{"x":0.095916748046875,"y":0.298553466796875},{"x":0.0496826171875,"y":0.0074462890625},{"x":-0.14105224609375,"y":0.287811279296875}],"optimisedCameraToObject":{"translation":{"x":-0.16474605442443782,"y":-0.13756812250190248,"z":0.45451932807657547},"rotation":{"quaternion":{"W":0.9965723249910379,"X":0.04979101897245024,"Y":-0.058486485323024306,"Z":0.03072110880489241}}},"includeObservationInCalibration":true,"snapshotName":"img16.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":160.26551818847656,"y":272.7175598144531},{"x":195.88360595703125,"y":275.1936340332031},{"x":231.47735595703125,"y":277.8559875488281},{"x":267.0601806640625,"y":280.1815185546875},{"x":301.7333068847656,"y":282.92889404296875},{"x":336.9476013183594,"y":285.23065185546875},{"x":371.40838623046875,"y":288.21868896484375},{"x":159.40530395507812,"y":307.0029296875},{"x":195.26065063476562,"y":309.3342590332031},{"x":230.195556640625,"y":312.2760314941406},{"x":265.2735290527344,"y":314.5755310058594},{"x":299.4888610839844,"y":316.6572265625},{"x":334.62982177734375,"y":319.2293395996094},{"x":368.6734313964844,"y":321.7421875},{"x":159.04246520996094,"y":340.8913879394531},{"x":193.65792846679688,"y":342.9244384765625},{"x":228.91427612304688,"y":345.376953125},{"x":263.43255615234375,"y":347.7806396484375},{"x":297.80975341796875,"y":350.1204833984375},{"x":332.1525573730469,"y":352.4575500488281},{"x":365.96124267578125,"y":355.0853271484375},{"x":158.5865478515625,"y":374.194580078125},{"x":193.12576293945312,"y":376.2279968261719},{"x":227.3429718017578,"y":378.2856140136719},{"x":261.91351318359375,"y":380.769287109375},{"x":295.6500549316406,"y":382.97076416015625},{"x":329.76055908203125,"y":385.4019775390625},{"x":363.3720703125,"y":387.3465270996094},{"x":157.8304901123047,"y":406.03533935546875},{"x":192.0241241455078,"y":408.03607177734375},{"x":226.2036590576172,"y":410.28558349609375},{"x":260.2247009277344,"y":412.803955078125},{"x":293.8889465332031,"y":414.9324645996094},{"x":327.67071533203125,"y":416.85906982421875},{"x":361.02801513671875,"y":419.10198974609375},{"x":156.90638732910156,"y":437.9564514160156},{"x":191.2289581298828,"y":440.166015625},{"x":224.82415771484375,"y":442.2236022949219},{"x":258.4577941894531,"y":444.5066833496094},{"x":291.90069580078125,"y":446.6847839355469},{"x":324.962646484375,"y":449.098876953125},{"x":358.1766662597656,"y":450.8293151855469},{"x":156.5986785888672,"y":469.13006591796875},{"x":190.12892150878906,"y":471.2291259765625},{"x":223.61407470703125,"y":473.41015625},{"x":256.6712951660156,"y":475.2705383300781},{"x":289.9999084472656,"y":477.67413330078125},{"x":323.01513671875,"y":479.81353759765625},{"x":355.99945068359375,"y":481.8311462402344}],"reprojectionErrors":[{"x":0.131683349609375,"y":-0.2236328125},{"x":0.08544921875,"y":-0.06707763671875},{"x":-0.07623291015625,"y":-0.11651611328125},{"x":-0.373565673828125,"y":0.15069580078125},{"x":0.085601806640625,"y":-0.0245361328125},{"x":-0.1561279296875,"y":0.224853515625},{"x":0.189483642578125,"y":-0.23345947265625},{"x":0.2985687255859375,"y":-0.036376953125},{"x":-0.335235595703125,"y":0.167510986328125},{"x":-0.1854705810546875,"y":-0.260650634765625},{"x":-0.322265625,"y":-0.06854248046875},{"x":0.253509521484375,"y":0.319000244140625},{"x":-0.2528076171875,"y":0.193389892578125},{"x":0.17547607421875,"y":0.103912353515625},{"x":-0.009490966796875,"y":-0.137054443359375},{"x":0.251495361328125,"y":0.2708740234375},{"x":-0.262420654296875,"y":0.235931396484375},{"x":-0.178802490234375,"y":0.226104736328125},{"x":-0.10107421875,"y":0.256011962890625},{"x":-0.1422119140625,"y":0.264251708984375},{"x":0.19134521484375,"y":-0.04296875},{"x":-0.202606201171875,"y":-0.321868896484375},{"x":-0.2053680419921875,"y":-0.0054931640625},{"x":-0.017333984375,"y":0.261627197265625},{"x":-0.320281982421875,"y":0.077239990234375},{"x":0.06683349609375,"y":0.149322509765625},{"x":-0.0701904296875,"y":-0.034393310546875},{"x":0.1356201171875,"y":0.242218017578125},{"x":-0.07427978515625,"y":0.3013916015625},{"x":-0.0664215087890625,"y":0.562286376953125},{"x":-0.1729583740234375,"y":0.547698974609375},{"x":-0.255828857421875,"y":0.2371826171875},{"x":-0.1229248046875,"y":0.289215087890625},{"x":-0.254638671875,"y":0.515533447265625},{"x":-0.11492919921875,"y":0.397674560546875},{"x":0.24285888671875,"y":0.204559326171875},{"x":-0.208251953125,"y":0.171356201171875},{"x":-0.057861328125,"y":0.261810302734375},{"x":-0.077972412109375,"y":0.098175048828125},{"x":-0.045501708984375,"y":0.010650634765625},{"x":0.22381591796875,"y":-0.34197998046875},{"x":0.1910400390625,"y":-0.040252685546875},{"x":-0.0361328125,"y":0.22979736328125},{"x":-0.0201416015625,"y":0.224578857421875},{"x":-0.08233642578125,"y":0.1075439453125},{"x":0.15399169921875,"y":0.281097412109375},{"x":-0.016387939453125,"y":-0.118927001953125},{"x":-0.0146484375,"y":-0.2852783203125},{"x":-0.128997802734375,"y":-0.36053466796875}],"optimisedCameraToObject":{"translation":{"x":-0.1753115920804864,"y":-0.043666000458725415,"z":0.48654877691340925},"rotation":{"quaternion":{"W":0.9941663820482253,"X":0.09919308416060063,"Y":-0.018036637810928277,"Z":0.038322533271270824}}},"includeObservationInCalibration":true,"snapshotName":"img17.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":237.299072265625,"y":286.8665466308594},{"x":272.99066162109375,"y":288.5672302246094},{"x":308.3810729980469,"y":291.0510559082031},{"x":343.4644775390625,"y":292.853271484375},{"x":378.30926513671875,"y":294.9846496582031},{"x":412.9327697753906,"y":297.1768493652344},{"x":446.91314697265625,"y":299.0771789550781},{"x":236.1217041015625,"y":320.85430908203125},{"x":271.66583251953125,"y":322.9089050292969},{"x":306.41009521484375,"y":324.9311828613281},{"x":341.43743896484375,"y":326.9419860839844},{"x":375.86285400390625,"y":328.8192138671875},{"x":410.0010681152344,"y":330.8968200683594},{"x":443.73968505859375,"y":332.1127624511719},{"x":235.51800537109375,"y":354.6820068359375},{"x":270.1289367675781,"y":356.13787841796875},{"x":304.99749755859375,"y":358.0947570800781},{"x":339.22900390625,"y":359.9287414550781},{"x":372.9646301269531,"y":362.022216796875},{"x":407.3037109375,"y":363.8982238769531},{"x":440.774658203125,"y":365.3619079589844},{"x":234.11082458496094,"y":387.47430419921875},{"x":268.93536376953125,"y":389.2257080078125},{"x":302.982421875,"y":391.10528564453125},{"x":337.22760009765625,"y":392.86090087890625},{"x":370.87017822265625,"y":394.6519775390625},{"x":404.6983642578125,"y":396.0712890625},{"x":437.72119140625,"y":397.9093017578125},{"x":233.04754638671875,"y":419.73846435546875},{"x":267.0989990234375,"y":421.1092529296875},{"x":301.0884094238281,"y":422.9915771484375},{"x":335.1882629394531,"y":424.4372253417969},{"x":368.6764831542969,"y":425.9659729003906},{"x":401.8834228515625,"y":427.7222595214844},{"x":434.8236999511719,"y":429.194091796875},{"x":231.87452697753906,"y":451.18218994140625},{"x":266.0405578613281,"y":452.9459533691406},{"x":299.6012268066406,"y":454.3401184082031},{"x":333.06744384765625,"y":456.0312805175781},{"x":366.0672607421875,"y":457.38043212890625},{"x":399.13494873046875,"y":459.18988037109375},{"x":431.918701171875,"y":460.85809326171875},{"x":230.88746643066406,"y":482.38348388671875},{"x":264.423583984375,"y":483.84490966796875},{"x":297.7781066894531,"y":485.5733947753906},{"x":331.1012268066406,"y":486.8656005859375},{"x":363.9580078125,"y":488.1300048828125},{"x":396.6248779296875,"y":489.7809143066406},{"x":428.95220947265625,"y":491.3472595214844}],"reprojectionErrors":[{"x":0.2255096435546875,"y":-0.311431884765625},{"x":0.038177490234375,"y":0.144622802734375},{"x":-0.06170654296875,"y":-0.205352783203125},{"x":-0.074005126953125,"y":0.103118896484375},{"x":-0.072479248046875,"y":0.059051513671875},{"x":-0.079864501953125,"y":-0.0694580078125},{"x":0.32061767578125,"y":0.070098876953125},{"x":0.26556396484375,"y":0.04718017578125},{"x":-0.124298095703125,"y":0.024169921875},{"x":0.0762939453125,"y":0.009124755859375},{"x":-0.22113037109375,"y":-0.019012451171875},{"x":-0.13690185546875,"y":0.0616455078125},{"x":0.00897216796875,"y":-0.082977294921875},{"x":0.3238525390625,"y":0.60894775390625},{"x":-0.2408905029296875,"y":-0.122344970703125},{"x":-0.042327880859375,"y":0.3326416015625},{"x":-0.306549072265625,"y":0.2608642578125},{"x":-0.144317626953125,"y":0.28607177734375},{"x":0.29791259765625,"y":0.025665283203125},{"x":-0.0843505859375,"y":-0.04345703125},{"x":0.175506591796875,"y":0.27337646484375},{"x":0.0826263427734375,"y":0.071075439453125},{"x":-0.272064208984375,"y":0.11407470703125},{"x":-0.050262451171875,"y":0.001800537109375},{"x":-0.23297119140625,"y":-0.013763427734375},{"x":-0.024658203125,"y":-0.092132568359375},{"x":-0.218597412109375,"y":0.173797607421875},{"x":0.1712646484375,"y":-0.006500244140625},{"x":0.0881195068359375,"y":0.135467529296875},{"x":0.171905517578125,"y":0.44677734375},{"x":0.120758056640625,"y":0.2181396484375},{"x":-0.243072509765625,"y":0.39764404296875},{"x":-0.20263671875,"y":0.4654541015625},{"x":-0.093292236328125,"y":0.277099609375},{"x":0.065521240234375,"y":0.344451904296875},{"x":0.228607177734375,"y":0.3780517578125},{"x":-0.131866455078125,"y":0.188018798828125},{"x":-0.08001708984375,"y":0.337921142578125},{"x":-0.131927490234375,"y":0.161102294921875},{"x":0.07928466796875,"y":0.296478271484375},{"x":0.014434814453125,"y":-0.0582275390625},{"x":0.020538330078125,"y":-0.301544189453125},{"x":0.2077789306640625,"y":0.235260009765625},{"x":0.152374267578125,"y":0.243072509765625},{"x":0.08935546875,"y":-0.047088623046875},{"x":-0.136566162109375,"y":0.068115234375},{"x":-0.09539794921875,"y":0.180206298828125},{"x":-0.068450927734375,"y":-0.125152587890625},{"x":0.0892333984375,"y":-0.3768310546875}],"optimisedCameraToObject":{"translation":{"x":-0.120077643813806,"y":-0.03325096713216061,"z":0.4860159725300603},"rotation":{"quaternion":{"W":0.9940334673230898,"X":0.10018342340729534,"Y":-0.027929824547626648,"Z":0.03287358235375339}}},"includeObservationInCalibration":true,"snapshotName":"img18.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":237.25791931152344,"y":292.55426025390625},{"x":272.83160400390625,"y":294.8651428222656},{"x":308.0140380859375,"y":297.2074890136719},{"x":342.9413757324219,"y":299.2397766113281},{"x":377.3575134277344,"y":301.60601806640625},{"x":411.9292297363281,"y":303.8905944824219},{"x":445.7149658203125,"y":306.2012939453125},{"x":236.04196166992188,"y":326.6026306152344},{"x":271.2687072753906,"y":328.7168884277344},{"x":305.80303955078125,"y":330.8786315917969},{"x":340.4033508300781,"y":333.1482849121094},{"x":374.52203369140625,"y":334.95758056640625},{"x":408.93145751953125,"y":337.1377868652344},{"x":442.4022521972656,"y":338.9502868652344},{"x":235.01246643066406,"y":359.7694396972656},{"x":269.40533447265625,"y":361.5374450683594},{"x":304.013427734375,"y":363.8246154785156},{"x":338.03887939453125,"y":365.481689453125},{"x":371.95758056640625,"y":367.8439025878906},{"x":406.0009765625,"y":369.9101257324219},{"x":439.2597351074219,"y":371.49945068359375},{"x":233.6402587890625,"y":392.2527160644531},{"x":267.9810791015625,"y":394.38983154296875},{"x":302.01806640625,"y":396.0508117675781},{"x":335.9541320800781,"y":398.1384582519531},{"x":369.4820556640625,"y":400.0735168457031},{"x":403.0712585449219,"y":401.8822937011719},{"x":435.952880859375,"y":403.8533020019531},{"x":232.5345916748047,"y":423.9532470703125},{"x":266.5255432128906,"y":425.7818908691406},{"x":300.1537780761719,"y":427.8794860839844},{"x":333.7389831542969,"y":429.27215576171875},{"x":366.9523620605469,"y":431.1911926269531},{"x":400.0719299316406,"y":432.8009948730469},{"x":432.878173828125,"y":434.66796875},{"x":231.15626525878906,"y":455.4431457519531},{"x":264.9363098144531,"y":457.0746765136719},{"x":298.2123718261719,"y":458.881591796875},{"x":331.6088562011719,"y":460.1883850097656},{"x":364.2332763671875,"y":462.11016845703125},{"x":397.2676086425781,"y":464.05950927734375},{"x":429.5316467285156,"y":465.2807312011719},{"x":230.10865783691406,"y":485.9787292480469},{"x":263.2046813964844,"y":487.3025207519531},{"x":296.48486328125,"y":489.2945861816406},{"x":329.3624267578125,"y":490.7539978027344},{"x":361.9385986328125,"y":492.32037353515625},{"x":394.4825439453125,"y":493.9151916503906},{"x":426.77606201171875,"y":495.8111572265625}],"reprojectionErrors":[{"x":0.129974365234375,"y":-0.0556640625},{"x":-0.1085205078125,"y":-0.037689208984375},{"x":-0.170196533203125,"y":-0.076263427734375},{"x":-0.19677734375,"y":0.169830322265625},{"x":0.06256103515625,"y":0.056365966796875},{"x":-0.064178466796875,"y":-0.00128173828125},{"x":0.359527587890625,"y":-0.111114501953125},{"x":0.0801849365234375,"y":-0.093902587890625},{"x":-0.17950439453125,"y":-0.007293701171875},{"x":0.04339599609375,"y":0.005401611328125},{"x":-0.014923095703125,"y":-0.116546630859375},{"x":0.1878662109375,"y":0.19500732421875},{"x":-0.125701904296875,"y":0.10858154296875},{"x":0.268829345703125,"y":0.36260986328125},{"x":-0.12493896484375,"y":0.029022216796875},{"x":0.087127685546875,"y":0.338623046875},{"x":-0.121337890625,"y":0.101318359375},{"x":0.042144775390625,"y":0.466156005859375},{"x":0.096588134765625,"y":0.097747802734375},{"x":-0.194549560546875,"y":-0.0029296875},{"x":0.0732421875,"y":0.344940185546875},{"x":0.0429840087890625,"y":0.13299560546875},{"x":-0.04913330078125,"y":-0.045196533203125},{"x":-0.03839111328125,"y":0.2237548828125},{"x":-0.13287353515625,"y":0.036834716796875},{"x":-0.030517578125,"y":-0.0267333984375},{"x":-0.2056884765625,"y":0.006561279296875},{"x":0.105712890625,"y":-0.151885986328125},{"x":-0.0260772705078125,"y":0.334716796875},{"x":-0.11883544921875,"y":0.350677490234375},{"x":-0.0455322265625,"y":0.067474365234375},{"x":-0.131072998046875,"y":0.4588623046875},{"x":-0.0516357421875,"y":0.293487548828125},{"x":-0.090087890625,"y":0.406829833984375},{"x":-0.03167724609375,"y":0.232452392578125},{"x":0.2063140869140625,"y":0.078887939453125},{"x":-0.0203857421875,"y":0.181884765625},{"x":0.0643310546875,"y":0.078094482421875},{"x":-0.168975830078125,"y":0.442962646484375},{"x":0.167236328125,"y":0.161346435546875},{"x":-0.11376953125,"y":-0.179351806640625},{"x":0.16351318359375,"y":0.17645263671875},{"x":0.1360626220703125,"y":0.1256103515625},{"x":0.253997802734375,"y":0.4302978515625},{"x":-7.32421875E-4,"y":0.034210205078125},{"x":-0.046356201171875,"y":0.138214111328125},{"x":0.0111083984375,"y":0.10272216796875},{"x":-0.102294921875,"y":0.006195068359375},{"x":-0.172882080078125,"y":-0.42401123046875}],"optimisedCameraToObject":{"translation":{"x":-0.12044170011989679,"y":-0.02906312498524957,"z":0.48790735444749955},"rotation":{"quaternion":{"W":0.9932715454145365,"X":0.10653308304703156,"Y":-0.027799516241507824,"Z":0.035909973308967266}}},"includeObservationInCalibration":true,"snapshotName":"img19.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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":205.10565185546875,"y":291.9783630371094},{"x":239.94932556152344,"y":295.44097900390625},{"x":274.6065979003906,"y":298.9404602050781},{"x":309.19268798828125,"y":302.4843444824219},{"x":343.50250244140625,"y":306.2490234375},{"x":378.12286376953125,"y":309.4586181640625},{"x":412.1042175292969,"y":312.9718933105469},{"x":203.35182189941406,"y":325.5445861816406},{"x":237.86865234375,"y":328.9479064941406},{"x":272.10772705078125,"y":332.2984313964844},{"x":306.1739196777344,"y":336.0998840332031},{"x":340.2659912109375,"y":339.60003662109375},{"x":374.4324645996094,"y":342.9143371582031},{"x":408.437255859375,"y":346.14447021484375},{"x":201.40093994140625,"y":358.6287841796875},{"x":235.3829803466797,"y":361.6885681152344},{"x":269.5810546875,"y":364.9986877441406},{"x":303.4736328125,"y":368.2331848144531},{"x":337.06976318359375,"y":371.966064453125},{"x":370.9389953613281,"y":375.40655517578125},{"x":404.63348388671875,"y":378.72589111328125},{"x":199.79217529296875,"y":391.0230407714844},{"x":233.54922485351562,"y":394.2126770019531},{"x":267.067626953125,"y":397.4864807128906},{"x":300.750244140625,"y":400.99755859375},{"x":334.1797790527344,"y":404.2261047363281},{"x":367.87017822265625,"y":407.6087341308594},{"x":400.82958984375,"y":410.6313781738281},{"x":197.92198181152344,"y":422.27398681640625},{"x":231.09629821777344,"y":425.1934814453125},{"x":264.6482849121094,"y":428.81256103515625},{"x":297.9969787597656,"y":431.92425537109375},{"x":331.11083984375,"y":435.20733642578125},{"x":364.4385986328125,"y":438.3575439453125},{"x":397.276123046875,"y":441.85955810546875},{"x":196.3050994873047,"y":453.31884765625},{"x":229.6171112060547,"y":456.65960693359375},{"x":262.2696533203125,"y":459.7550354003906},{"x":295.460205078125,"y":463.0153503417969},{"x":328.1221008300781,"y":466.1530456542969},{"x":360.9857177734375,"y":469.7958679199219},{"x":393.6920166015625,"y":473.16229248046875},{"x":194.73199462890625,"y":483.7914123535156},{"x":227.05288696289062,"y":486.9148254394531},{"x":260.13983154296875,"y":490.3260192871094},{"x":292.7618713378906,"y":493.52716064453125},{"x":325.1023864746094,"y":496.80108642578125},{"x":357.75872802734375,"y":499.8298034667969},{"x":389.9835510253906,"y":503.1544494628906}],"reprojectionErrors":[{"x":0.0834808349609375,"y":-0.03680419921875},{"x":-0.110626220703125,"y":0.04754638671875},{"x":-0.151763916015625,"y":0.080596923828125},{"x":-0.1624755859375,"y":0.054168701171875},{"x":0.055023193359375,"y":-0.20892333984375},{"x":-0.0933837890625,"y":0.066497802734375},{"x":0.334625244140625,"y":0.021026611328125},{"x":-0.020538330078125,"y":0.02130126953125},{"x":-0.231353759765625,"y":0.110107421875},{"x":-0.1968994140625,"y":0.235137939453125},{"x":-0.029296875,"y":-0.1080322265625},{"x":0.0655517578125,"y":-0.1678466796875},{"x":0.032012939453125,"y":-0.060455322265625},{"x":0.099029541015625,"y":0.111785888671875},{"x":0.116943359375,"y":-0.110321044921875},{"x":0.10260009765625,"y":0.26849365234375},{"x":-0.159393310546875,"y":0.378326416015625},{"x":-0.15460205078125,"y":0.544464111328125},{"x":0.1009521484375,"y":0.1922607421875},{"x":0.03070068359375,"y":0.11175537109375},{"x":0.075531005859375,"y":0.131134033203125},{"x":-0.044281005859375,"y":-0.208404541015625},{"x":-0.1668548583984375,"y":-0.011688232421875},{"x":-0.08154296875,"y":0.080230712890625},{"x":-0.198150634765625,"y":-0.08642578125},{"x":-0.106231689453125,"y":0.007537841796875},{"x":-0.32659912109375,"y":-0.075164794921875},{"x":0.125732421875,"y":0.178924560546875},{"x":0.0982818603515625,"y":0.19537353515625},{"x":0.2302093505859375,"y":0.6112060546875},{"x":-0.045440673828125,"y":0.304931640625},{"x":-0.154510498046875,"y":0.48284912109375},{"x":-0.072235107421875,"y":0.465606689453125},{"x":-0.254058837890625,"y":0.556793212890625},{"x":-0.002532958984375,"y":0.27117919921875},{"x":0.02886962890625,"y":0.17828369140625},{"x":-0.3001861572265625,"y":0.123016357421875},{"x":0.0010986328125,"y":0.28875732421875},{"x":-0.271392822265625,"y":0.26458740234375},{"x":-0.057647705078125,"y":0.337493896484375},{"x":-0.0946044921875,"y":-0.120941162109375},{"x":-0.02984619140625,"y":-0.3297119140625},{"x":-0.0439300537109375,"y":0.12066650390625},{"x":0.29962158203125,"y":0.234100341796875},{"x":-0.151214599609375,"y":0.03363037109375},{"x":-0.1719970703125,"y":0.016510009765625},{"x":0.04736328125,"y":-0.100677490234375},{"x":-0.096954345703125,"y":-5.4931640625E-4},{"x":0.136016845703125,"y":-0.22479248046875}],"optimisedCameraToObject":{"translation":{"x":-0.1444603335331757,"y":-0.030404896992126864,"z":0.495286899645309},"rotation":{"quaternion":{"W":0.9935961722437695,"X":0.10069740179682722,"Y":-0.0020582638348391586,"Z":0.05120979714746115}}},"includeObservationInCalibration":true,"snapshotName":"img20.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/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.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.83456420898438,"y":296.89715576171875},{"x":254.24002075195312,"y":301.42095947265625},{"x":286.8036804199219,"y":306.6441955566406},{"x":320.20489501953125,"y":311.66754150390625},{"x":353.6714172363281,"y":316.728271484375},{"x":387.8068542480469,"y":321.7738952636719},{"x":422.03546142578125,"y":326.951171875},{"x":219.277587890625,"y":329.386962890625},{"x":251.4307098388672,"y":334.3419494628906},{"x":283.6063232421875,"y":339.70355224609375},{"x":316.5751647949219,"y":344.91058349609375},{"x":349.55694580078125,"y":349.8240051269531},{"x":383.6032409667969,"y":355.2890319824219},{"x":417.7720031738281,"y":360.52203369140625},{"x":216.86907958984375,"y":361.63421630859375},{"x":248.5254364013672,"y":366.6168212890625},{"x":280.7945251464844,"y":371.8406066894531},{"x":313.29486083984375,"y":377.10528564453125},{"x":345.91595458984375,"y":382.8291320800781},{"x":379.39862060546875,"y":388.3311462402344},{"x":412.92169189453125,"y":393.7823791503906},{"x":214.70777893066406,"y":392.9633483886719},{"x":246.13912963867188,"y":398.3952331542969},{"x":277.6194763183594,"y":404.005615234375},{"x":309.6116638183594,"y":409.62298583984375},{"x":342.3776550292969,"y":415.0847473144531},{"x":375.45782470703125,"y":420.7248229980469},{"x":408.8182373046875,"y":426.4452209472656},{"x":212.2794647216797,"y":423.63482666015625},{"x":243.24232482910156,"y":429.1402893066406},{"x":274.7992858886719,"y":434.8668212890625},{"x":306.69940185546875,"y":440.710693359375},{"x":338.7595520019531,"y":446.4786682128906},{"x":371.6744079589844,"y":452.53411865234375},{"x":404.6105651855469,"y":458.5321960449219},{"x":209.92945861816406,"y":454.25665283203125},{"x":240.64459228515625,"y":459.9393005371094},{"x":271.74884033203125,"y":465.6007080078125},{"x":303.5716857910156,"y":471.75177001953125},{"x":335.2811584472656,"y":477.7835693359375},{"x":367.634521484375,"y":483.88330078125},{"x":400.1826171875,"y":489.9425964355469},{"x":207.46145629882812,"y":484.11260986328125},{"x":237.98487854003906,"y":489.9325256347656},{"x":268.79022216796875,"y":496.08447265625},{"x":300.03961181640625,"y":502.2381286621094},{"x":331.57110595703125,"y":508.223388671875},{"x":363.7362060546875,"y":514.6088256835938},{"x":396.0698547363281,"y":520.8773803710938}],"reprojectionErrors":[{"x":0.1796875,"y":-0.1329345703125},{"x":-0.0954437255859375,"y":0.2276611328125},{"x":-0.041900634765625,"y":-0.048095703125},{"x":-0.335235595703125,"y":-0.060455322265625},{"x":-0.199462890625,"y":-0.04644775390625},{"x":-0.234527587890625,"y":0.046783447265625},{"x":0.138824462890625,"y":0.07275390625},{"x":0.1864776611328125,"y":0.033416748046875},{"x":-0.1408233642578125,"y":0.1556396484375},{"x":-0.0123291015625,"y":-0.065643310546875},{"x":-0.195098876953125,"y":-0.069000244140625},{"x":0.094696044921875,"y":0.284942626953125},{"x":-0.191009521484375,"y":0.151153564453125},{"x":-0.1068115234375,"y":0.3135986328125},{"x":0.101287841796875,"y":-0.137725830078125},{"x":-0.029327392578125,"y":0.1419677734375},{"x":-0.30279541015625,"y":0.243438720703125},{"x":-0.3341064453125,"y":0.367218017578125},{"x":-0.00933837890625,"y":0.09527587890625},{"x":-0.066009521484375,"y":0.108856201171875},{"x":0.3203125,"y":0.237060546875},{"x":-0.175750732421875,"y":0.04034423828125},{"x":-0.37713623046875,"y":0.048248291015625},{"x":-0.165863037109375,"y":-0.059539794921875},{"x":-0.001373291015625,"y":-0.111328125},{"x":-0.142333984375,"y":0.0556640625},{"x":-0.1259765625,"y":0.107666015625},{"x":0.084716796875,"y":0.14288330078125},{"x":-0.131561279296875,"y":0.317901611328125},{"x":-0.156005859375,"y":0.4224853515625},{"x":-0.320892333984375,"y":0.3685302734375},{"x":-0.3720703125,"y":0.259918212890625},{"x":-0.123260498046875,"y":0.290069580078125},{"x":-0.266082763671875,"y":0.095703125},{"x":0.035797119140625,"y":0.02178955078125},{"x":-0.112579345703125,"y":0.0975341796875},{"x":-0.1766815185546875,"y":0.188140869140625},{"x":-0.184112548828125,"y":0.3621826171875},{"x":-0.46124267578125,"y":0.10894775390625},{"x":-0.173095703125,"y":0.03741455078125},{"x":-0.074005126953125,"y":-0.039520263671875},{"x":0.287933349609375,"y":-0.013397216796875},{"x":0.0764312744140625,"y":0.1058349609375},{"x":-0.07928466796875,"y":0.215576171875},{"x":-0.07879638671875,"y":0.05511474609375},{"x":-0.081268310546875,"y":-0.04510498046875},{"x":0.078125,"y":0.0850830078125},{"x":0.050628662109375,"y":-0.12286376953125},{"x":0.304046630859375,"y":-0.15185546875}],"optimisedCameraToObject":{"translation":{"x":-0.13480977528488933,"y":-0.027969011362889956,"z":0.5153615289954407},"rotation":{"quaternion":{"W":0.9909360988225843,"X":0.0871584029591874,"Y":0.07865896851506536,"Z":0.06528267393441664}}},"includeObservationInCalibration":true,"snapshotName":"img21.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img21.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":273.29534912109375,"y":298.1326904296875},{"x":305.9515380859375,"y":301.1636962890625},{"x":339.3200378417969,"y":304.5674743652344},{"x":373.2886962890625,"y":307.8554382324219},{"x":407.53680419921875,"y":311.25189208984375},{"x":442.29632568359375,"y":314.6498107910156},{"x":477.8211669921875,"y":318.41070556640625},{"x":271.8194885253906,"y":331.2152099609375},{"x":304.8092346191406,"y":334.7142333984375},{"x":337.31109619140625,"y":337.9703369140625},{"x":370.87628173828125,"y":341.93060302734375},{"x":404.7430725097656,"y":345.5891418457031},{"x":439.882568359375,"y":349.10662841796875},{"x":474.5042724609375,"y":352.4245910644531},{"x":270.4390869140625,"y":363.8553466796875},{"x":302.5592346191406,"y":367.2923278808594},{"x":335.3482360839844,"y":371.1324157714844},{"x":368.3153076171875,"y":374.4293518066406},{"x":402.0694885253906,"y":379.07635498046875},{"x":436.4385681152344,"y":382.52679443359375},{"x":471.5690612792969,"y":386.81878662109375},{"x":269.3453369140625,"y":395.74066162109375},{"x":301.283935546875,"y":399.8152770996094},{"x":333.4527893066406,"y":403.8787841796875},{"x":366.2280578613281,"y":407.94769287109375},{"x":399.50836181640625,"y":411.8315734863281},{"x":433.6887512207031,"y":416.33135986328125},{"x":468.0879211425781,"y":420.1074523925781},{"x":267.9858703613281,"y":426.98883056640625},{"x":299.7019958496094,"y":431.1611328125},{"x":331.33642578125,"y":435.3774719238281},{"x":364.2884521484375,"y":439.9194641113281},{"x":397.2591857910156,"y":444.1138000488281},{"x":431.10693359375,"y":448.3982238769531},{"x":465.14642333984375,"y":453.09429931640625},{"x":266.5639343261719,"y":458.08367919921875},{"x":298.15924072265625,"y":462.63189697265625},{"x":329.7684631347656,"y":466.9753112792969},{"x":362.11083984375,"y":471.44439697265625},{"x":394.8540344238281,"y":476.1927795410156},{"x":427.86859130859375,"y":481.2795715332031},{"x":462.1605224609375,"y":486.0140686035156},{"x":265.30596923828125,"y":488.6055908203125},{"x":296.1524658203125,"y":492.899169921875},{"x":327.7750549316406,"y":498.2210998535156},{"x":359.7512512207031,"y":502.6278991699219},{"x":392.3768615722656,"y":507.77685546875},{"x":425.5109558105469,"y":512.5757446289062},{"x":459.2100830078125,"y":517.9026489257812}],"reprojectionErrors":[{"x":0.16204833984375,"y":-0.04644775390625},{"x":0.0906982421875,"y":0.164642333984375},{"x":-0.11419677734375,"y":0.051483154296875},{"x":-0.332489013671875,"y":0.103240966796875},{"x":-0.23529052734375,"y":0.096160888671875},{"x":-0.046478271484375,"y":0.1378173828125},{"x":-0.01177978515625,"y":-0.132720947265625},{"x":0.18157958984375,"y":-0.069580078125},{"x":-0.494293212890625,"y":-0.06915283203125},{"x":-0.11273193359375,"y":0.224456787109375},{"x":-0.21710205078125,"y":-0.135345458984375},{"x":-0.037841796875,"y":-0.142059326171875},{"x":-0.53814697265625,"y":0.044158935546875},{"x":0.080322265625,"y":0.482330322265625},{"x":0.138427734375,"y":-0.173858642578125},{"x":0.064300537109375,"y":0.1373291015625},{"x":-0.118133544921875,"y":0.09716796875},{"x":0.089508056640625,"y":0.65252685546875},{"x":0.085845947265625,"y":-0.08929443359375},{"x":0.0506591796875,"y":0.41888427734375},{"x":-0.1549072265625,"y":0.139404296875},{"x":-0.1591796875,"y":-0.038818359375},{"x":-0.3165283203125,"y":-0.125030517578125},{"x":-0.15240478515625,"y":-0.14691162109375},{"x":-0.035614013671875,"y":-0.120391845703125},{"x":0.14263916015625,"y":0.14544677734375},{"x":-0.005340576171875,"y":-0.14984130859375},{"x":0.20916748046875,"y":0.333892822265625},{"x":-0.15948486328125,"y":0.2257080078125},{"x":-0.356048583984375,"y":0.27386474609375},{"x":0.072113037109375,"y":0.33258056640625},{"x":-0.26708984375,"y":0.120697021484375},{"x":-0.067657470703125,"y":0.31201171875},{"x":-0.18072509765625,"y":0.46929931640625},{"x":0.086151123046875,"y":0.271484375},{"x":-0.066253662109375,"y":0.143707275390625},{"x":-0.400726318359375,"y":0.040069580078125},{"x":-0.21453857421875,"y":0.196990966796875},{"x":-0.22003173828125,"y":0.284454345703125},{"x":-0.07794189453125,"y":0.149383544921875},{"x":0.348175048828125,"y":-0.266937255859375},{"x":0.059173583984375,"y":-0.273345947265625},{"x":-0.10650634765625,"y":0.1424560546875},{"x":0.0521240234375,"y":0.50982666015625},{"x":-0.039154052734375,"y":-0.0943603515625},{"x":0.04888916015625,"y":0.27392578125},{"x":0.02716064453125,"y":-0.042205810546875},{"x":0.0433349609375,"y":0.0499267578125},{"x":0.047515869140625,"y":-0.327392578125}],"optimisedCameraToObject":{"translation":{"x":-0.0971020601485617,"y":-0.02593864395801202,"z":0.5148826016899422},"rotation":{"quaternion":{"W":0.9921238690308274,"X":0.07821680074117643,"Y":0.08912589827431254,"Z":0.04036006488985952}}},"includeObservationInCalibration":true,"snapshotName":"img22.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img22.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.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.05079999938607216,"y":0.1777999997138977,"z":0.0},{"x":0.07620000094175339,"y":0.1777999997138977,"z":0.0},{"x":0.15240000188350677,"y":0.1777999997138977,"z":0.0}],"locationInImageSpace":[{"x":468.2918395996094,"y":296.106689453125},{"x":503.1427917480469,"y":298.7600402832031},{"x":538.4879150390625,"y":301.4425964355469},{"x":574.1312866210938,"y":304.1048583984375},{"x":610.0447387695312,"y":307.3140563964844},{"x":430.15582275390625,"y":327.8674621582031},{"x":465.0914001464844,"y":330.5533447265625},{"x":500.1175537109375,"y":333.4758605957031},{"x":535.0822143554688,"y":336.2174987792969},{"x":570.7398681640625,"y":339.1258544921875},{"x":606.171142578125,"y":341.5516662597656},{"x":393.27813720703125,"y":358.5330810546875},{"x":427.5981140136719,"y":361.21429443359375},{"x":462.24127197265625,"y":364.1380615234375},{"x":496.54742431640625,"y":367.121826171875},{"x":531.6513061523438,"y":370.0340881347656},{"x":566.8878784179688,"y":373.0981140136719},{"x":602.1993408203125,"y":376.3245544433594},{"x":391.0768737792969,"y":391.7809143066406},{"x":425.14215087890625,"y":394.52630615234375},{"x":459.0600280761719,"y":397.5071105957031},{"x":493.3962707519531,"y":401.0244445800781},{"x":528.16845703125,"y":403.8939514160156},{"x":563.2645263671875,"y":407.0942077636719},{"x":598.5987548828125,"y":410.03741455078125},{"x":422.43670654296875,"y":426.96051025390625},{"x":456.1813659667969,"y":430.0790100097656},{"x":490.6443786621094,"y":433.4365539550781},{"x":524.7940063476562,"y":436.4040832519531},{"x":559.907470703125,"y":439.93731689453125},{"x":594.4887084960938,"y":443.41668701171875},{"x":419.745849609375,"y":459.8104248046875},{"x":453.426025390625,"y":462.6128234863281},{"x":487.55181884765625,"y":466.18951416015625},{"x":521.5829467773438,"y":469.70831298828125},{"x":556.5078735351562,"y":473.1047058105469},{"x":417.490478515625,"y":491.7756042480469},{"x":451.0010681152344,"y":495.0631103515625},{"x":553.0160522460938,"y":505.3081970214844}],"reprojectionErrors":[{"x":-0.38311767578125,"y":0.103363037109375},{"x":-0.06243896484375,"y":0.16339111328125},{"x":0.04510498046875,"y":0.20965576171875},{"x":0.131103515625,"y":0.291259765625},{"x":0.21905517578125,"y":-0.159454345703125},{"x":0.169097900390625,"y":-0.19097900390625},{"x":-0.12225341796875,"y":-0.056610107421875},{"x":-0.222625732421875,"y":-0.14459228515625},{"x":0.01593017578125,"y":-0.037872314453125},{"x":-0.16546630859375,"y":-0.08447265625},{"x":0.1480712890625,"y":0.364349365234375},{"x":0.2630615234375,"y":-0.0736083984375},{"x":0.065032958984375,"y":0.171356201171875},{"x":-0.17431640625,"y":0.186981201171875},{"x":0.201263427734375,"y":0.155303955078125},{"x":0.052978515625,"y":0.2073974609375},{"x":0.04150390625,"y":0.119476318359375},{"x":0.22015380859375,"y":-0.119659423828125},{"x":0.072906494140625,"y":-0.179718017578125},{"x":-0.105499267578125,"y":0.1181640625},{"x":0.14178466796875,"y":0.19232177734375},{"x":0.24505615234375,"y":-0.25885009765625},{"x":0.18267822265625,"y":-0.051513671875},{"x":0.06243896484375,"y":-0.164794921875},{"x":-0.034423828125,"y":-0.011444091796875},{"x":0.0084228515625,"y":0.496734619140625},{"x":0.191986083984375,"y":0.54534912109375},{"x":-0.071929931640625,"y":0.36456298828125},{"x":0.24432373046875,"y":0.582977294921875},{"x":-0.1407470703125,"y":0.24420166015625},{"x":0.2646484375,"y":-0.03271484375},{"x":0.142364501953125,"y":0.01800537109375},{"x":0.1552734375,"y":0.491424560546875},{"x":-0.010101318359375,"y":0.198760986328125},{"x":0.18255615234375,"y":-0.02838134765625},{"x":-0.2593994140625,"y":-0.126129150390625},{"x":-0.124908447265625,"y":-0.013275146484375},{"x":-0.17584228515625,"y":0.0804443359375},{"x":-0.244384765625,"y":0.01702880859375}],"optimisedCameraToObject":{"translation":{"x":-0.004001931220753106,"y":-0.030982526374607623,"z":0.5021405477424915},"rotation":{"quaternion":{"W":0.9963181190503495,"X":0.06513141171567187,"Y":0.042500968253930876,"Z":0.03608008532938393}}},"includeObservationInCalibration":true,"snapshotName":"img23.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img23.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":482.1957702636719,"y":290.4354553222656},{"x":516.843994140625,"y":292.57684326171875},{"x":551.3347778320312,"y":294.9490051269531},{"x":586.267333984375,"y":297.1055908203125},{"x":620.8065795898438,"y":299.3494873046875},{"x":655.568359375,"y":301.1884460449219},{"x":690.2613525390625,"y":303.9497375488281},{"x":479.16192626953125,"y":324.332763671875},{"x":513.6758422851562,"y":326.5758972167969},{"x":547.8634643554688,"y":328.419921875},{"x":582.96875,"y":331.16571044921875},{"x":617.506591796875,"y":333.3865661621094},{"x":652.2415161132812,"y":335.77276611328125},{"x":686.2088623046875,"y":337.69708251953125},{"x":476.7009582519531,"y":357.86236572265625},{"x":510.6234130859375,"y":359.9443359375},{"x":544.8506469726562,"y":362.2239074707031},{"x":578.8770141601562,"y":364.2187194824219},{"x":613.531982421875,"y":367.0957336425781},{"x":647.8619384765625,"y":369.0498046875},{"x":682.4725341796875,"y":371.5747985839844},{"x":473.8480224609375,"y":390.925048828125},{"x":507.73211669921875,"y":393.1667175292969},{"x":541.5873413085938,"y":395.46063232421875},{"x":575.7974853515625,"y":398.0694274902344},{"x":610.00732421875,"y":400.4812316894531},{"x":644.3345336914062,"y":402.9371337890625},{"x":678.472900390625,"y":404.9878845214844},{"x":471.0480651855469,"y":423.138671875},{"x":504.8868713378906,"y":425.3839416503906},{"x":538.5502319335938,"y":428.0508117675781},{"x":572.7108154296875,"y":430.4819641113281},{"x":606.2509765625,"y":432.857666015625},{"x":640.8463745117188,"y":435.0709533691406},{"x":674.7277221679688,"y":437.7785339355469},{"x":468.33349609375,"y":455.7919616699219},{"x":501.95001220703125,"y":458.14349365234375},{"x":535.3115844726562,"y":460.45391845703125},{"x":569.1876220703125,"y":462.9403076171875},{"x":602.9607543945312,"y":465.513916015625},{"x":636.8878173828125,"y":468.1390380859375},{"x":670.8754272460938,"y":470.7610778808594},{"x":465.7239074707031,"y":487.1983337402344},{"x":498.99853515625,"y":489.730712890625},{"x":532.685546875,"y":492.5281982421875},{"x":566.007080078125,"y":495.0296630859375},{"x":599.5563354492188,"y":497.6811828613281},{"x":633.0881958007812,"y":499.95343017578125},{"x":667.0059814453125,"y":502.67681884765625}],"reprojectionErrors":[{"x":-0.040863037109375,"y":-0.18994140625},{"x":-0.1661376953125,"y":-0.060302734375},{"x":-0.02496337890625,"y":-0.159454345703125},{"x":-0.2236328125,"y":-0.041534423828125},{"x":0.06597900390625,"y":-0.009918212890625},{"x":0.22088623046875,"y":0.427154541015625},{"x":0.52520751953125,"y":-0.05810546875},{"x":0.222503662109375,"y":-0.170135498046875},{"x":0.01739501953125,"y":-0.097564697265625},{"x":0.246337890625,"y":0.373779296875},{"x":-0.3414306640625,"y":-0.057464599609375},{"x":-0.26788330078125,"y":0.034912109375},{"x":-0.304443359375,"y":-0.03985595703125},{"x":0.50634765625,"y":0.34490966796875},{"x":-0.057159423828125,"y":-0.197418212890625},{"x":0.116119384765625,"y":0.07958984375},{"x":0.09124755859375,"y":0.15643310546875},{"x":0.36700439453125,"y":0.514984130859375},{"x":0.10711669921875,"y":-0.01226806640625},{"x":0.25830078125,"y":0.37933349609375},{"x":0.20782470703125,"y":0.19537353515625},{"x":0.084808349609375,"y":-0.169677734375},{"x":0.08447265625,"y":-0.010406494140625},{"x":0.21844482421875,"y":0.09185791015625},{"x":0.09625244140625,"y":-0.126007080078125},{"x":0.0662841796875,"y":-0.15264892578125},{"x":0.00408935546875,"y":-0.229766845703125},{"x":0.20892333984375,"y":0.0914306640625},{"x":0.203277587890625,"y":0.29827880859375},{"x":0.037353515625,"y":0.49456787109375},{"x":0.151123046875,"y":0.262420654296875},{"x":-0.13458251953125,"y":0.258575439453125},{"x":0.29107666015625,"y":0.302215576171875},{"x":-0.25421142578125,"y":0.499786376953125},{"x":-0.0081787109375,"y":0.1939697265625},{"x":0.265655517578125,"y":-0.079254150390625},{"x":0.11224365234375,"y":0.050140380859375},{"x":0.31695556640625,"y":0.21173095703125},{"x":0.10382080078125,"y":0.187835693359375},{"x":0.0836181640625,"y":0.066650390625},{"x":-0.0072021484375,"y":-0.116668701171875},{"x":-0.08203125,"y":-0.30810546875},{"x":0.252227783203125,"y":0.38739013671875},{"x":0.232025146484375,"y":0.37408447265625},{"x":-0.0985107421875,"y":0.08465576171875},{"x":0.03204345703125,"y":0.0797119140625},{"x":0.02398681640625,"y":-0.08740234375},{"x":0.11572265625,"y":0.112030029296875},{"x":-0.10272216796875,"y":-0.1529541015625}],"optimisedCameraToObject":{"translation":{"x":0.05776809839648845,"y":-0.03118119563322978,"z":0.5040427226881621},"rotation":{"quaternion":{"W":0.9974562098786715,"X":0.06120279982333776,"Y":0.017808462751924305,"Z":0.03190901632256216}}},"includeObservationInCalibration":true,"snapshotName":"img24.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img24.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":514.5296020507812,"y":301.00286865234375},{"x":548.6827392578125,"y":302.5894470214844},{"x":582.6654052734375,"y":303.99432373046875},{"x":616.832275390625,"y":305.2751159667969},{"x":650.9384765625,"y":307.00567626953125},{"x":685.708740234375,"y":308.418212890625},{"x":720.0001220703125,"y":310.0417785644531},{"x":512.157958984375,"y":333.8208923339844},{"x":545.93603515625,"y":335.31146240234375},{"x":579.6051635742188,"y":336.9882507324219},{"x":613.8090209960938,"y":338.5982360839844},{"x":647.8197631835938,"y":340.02691650390625},{"x":681.928955078125,"y":341.5901794433594},{"x":715.858154296875,"y":342.9744873046875},{"x":509.88812255859375,"y":366.0136413574219},{"x":543.0414428710938,"y":367.639892578125},{"x":576.8389892578125,"y":369.0639953613281},{"x":610.2348022460938,"y":370.8179626464844},{"x":644.02001953125,"y":372.4911804199219},{"x":678.0465087890625,"y":374.06463623046875},{"x":711.7077026367188,"y":375.7767333984375},{"x":507.4109802246094,"y":397.91455078125},{"x":540.4078979492188,"y":399.520751953125},{"x":573.8142700195312,"y":401.10186767578125},{"x":607.1807861328125,"y":403.0011291503906},{"x":640.6928100585938,"y":404.4811706542969},{"x":674.551025390625,"y":406.4023742675781},{"x":707.8875732421875,"y":407.9593811035156},{"x":504.9230651855469,"y":428.69195556640625},{"x":537.8804931640625,"y":430.3636169433594},{"x":570.8968505859375,"y":432.1441955566406},{"x":604.033203125,"y":433.8566589355469},{"x":637.201416015625,"y":435.8022766113281},{"x":670.618408203125,"y":437.323974609375},{"x":704.0753173828125,"y":439.16754150390625},{"x":502.61309814453125,"y":459.3592529296875},{"x":535.2446899414062,"y":461.3779602050781},{"x":567.8731079101562,"y":462.93212890625},{"x":601.0425415039062,"y":464.8209228515625},{"x":633.9627685546875,"y":466.8599853515625},{"x":666.9378662109375,"y":468.8481750488281},{"x":700.0917358398438,"y":470.5336608886719},{"x":500.60418701171875,"y":489.4859619140625},{"x":532.8828125,"y":491.39837646484375},{"x":565.3642578125,"y":493.39178466796875},{"x":597.9903564453125,"y":495.1634216308594},{"x":630.6166381835938,"y":497.10296630859375},{"x":663.4273681640625,"y":499.06134033203125},{"x":696.3583984375,"y":501.038818359375}],"reprojectionErrors":[{"x":0.07763671875,"y":-0.057952880859375},{"x":-0.12841796875,"y":-0.111297607421875},{"x":-0.01495361328125,"y":0.0155029296875},{"x":0.05712890625,"y":0.26446533203125},{"x":0.32647705078125,"y":0.061431884765625},{"x":0.06201171875,"y":0.173828125},{"x":0.40020751953125,"y":0.072296142578125},{"x":0.05413818359375,"y":-0.065582275390625},{"x":-0.0650634765625,"y":0.0413818359375},{"x":0.0712890625,"y":-0.04144287109375},{"x":-0.18658447265625,"y":-0.06134033203125},{"x":-0.116943359375,"y":0.0958251953125},{"x":-0.017578125,"y":0.11376953125},{"x":0.38360595703125,"y":0.30572509765625},{"x":-0.036163330078125,"y":0.003265380859375},{"x":0.18450927734375,"y":0.036407470703125},{"x":-0.09478759765625,"y":0.2662353515625},{"x":0.16595458984375,"y":0.160369873046875},{"x":0.16949462890625,"y":0.12908935546875},{"x":0.057861328125,"y":0.19097900390625},{"x":0.431396484375,"y":0.107269287109375},{"x":0.11529541015625,"y":-0.175537109375},{"x":0.21087646484375,"y":-0.062835693359375},{"x":0.03887939453125,"y":0.067657470703125},{"x":0.0428466796875,"y":-0.127685546875},{"x":0.03143310546875,"y":0.088134765625},{"x":-0.20208740234375,"y":-0.145721435546875},{"x":0.20391845703125,"y":-0.024261474609375},{"x":0.31146240234375,"y":0.238800048828125},{"x":0.16827392578125,"y":0.343292236328125},{"x":0.10577392578125,"y":0.329803466796875},{"x":0.05718994140625,"y":0.37493896484375},{"x":0.1048583984375,"y":0.176971435546875},{"x":0.02581787109375,"y":0.392608642578125},{"x":0.0228271484375,"y":0.275634765625},{"x":0.363067626953125,"y":0.241912841796875},{"x":0.2706298828125,"y":0.054412841796875},{"x":0.31890869140625,"y":0.320648193359375},{"x":-0.0421142578125,"y":0.24102783203125},{"x":-0.02789306640625,"y":-5.79833984375E-4},{"x":0.05157470703125,"y":-0.20343017578125},{"x":0.0665283203125,"y":-0.116119384765625},{"x":0.14642333984375,"y":0.273101806640625},{"x":0.13519287109375,"y":0.24481201171875},{"x":0.056396484375,"y":0.123077392578125},{"x":-0.03741455078125,"y":0.210113525390625},{"x":-0.00732421875,"y":0.115875244140625},{"x":-0.04345703125,"y":-0.01104736328125},{"x":-0.0875244140625,"y":-0.171417236328125}],"optimisedCameraToObject":{"translation":{"x":0.08349911855598952,"y":-0.022516339739823543,"z":0.5146657442104814},"rotation":{"quaternion":{"W":0.9957755350079717,"X":0.0861310210406133,"Y":0.024509569201674925,"Z":0.02029315430477627}}},"includeObservationInCalibration":true,"snapshotName":"img25.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img25.png"},{"locationInObjectSpace":[{"x":0.07620000094175339,"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.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.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":521.2957153320312,"y":177.27716064453125},{"x":626.6957397460938,"y":182.89825439453125},{"x":661.4932250976562,"y":184.82521057128906},{"x":448.86859130859375,"y":209.07960510253906},{"x":484.162353515625,"y":211.08653259277344},{"x":519.0791015625,"y":212.4941864013672},{"x":625.0225219726562,"y":218.34507751464844},{"x":659.46435546875,"y":219.86172485351562},{"x":482.1783752441406,"y":246.43948364257812},{"x":517.1153564453125,"y":248.09866333007812},{"x":552.4802856445312,"y":249.891845703125},{"x":587.6704711914062,"y":251.80735778808594},{"x":622.8319091796875,"y":253.53207397460938},{"x":657.6852416992188,"y":255.36453247070312},{"x":480.1801452636719,"y":281.88397216796875},{"x":515.2318115234375,"y":283.5365905761719},{"x":550.5081787109375,"y":285.410888671875},{"x":585.7969360351562,"y":287.16094970703125},{"x":620.8564453125,"y":288.9385681152344},{"x":655.7432250976562,"y":290.59576416015625},{"x":443.1548156738281,"y":315.0316162109375},{"x":478.19720458984375,"y":316.6027526855469},{"x":513.4869995117188,"y":318.4105529785156},{"x":548.6257934570312,"y":320.12432861328125},{"x":583.5635986328125,"y":322.0123596191406},{"x":618.98046875,"y":323.7330627441406},{"x":653.74169921875,"y":325.4056396484375},{"x":441.24688720703125,"y":350.4255676269531},{"x":476.53814697265625,"y":352.1204528808594},{"x":511.4320068359375,"y":354.0231628417969},{"x":546.8379516601562,"y":355.7093505859375},{"x":581.85595703125,"y":357.4516906738281},{"x":616.8963012695312,"y":359.1291809082031},{"x":652.02880859375,"y":360.8927307128906},{"x":439.5082702636719,"y":385.57720947265625},{"x":474.5896911621094,"y":387.2275390625},{"x":509.70867919921875,"y":388.9516906738281},{"x":544.9296875,"y":390.67779541015625},{"x":579.8626708984375,"y":392.3709411621094},{"x":615.2136840820312,"y":394.3392333984375},{"x":650.2600708007812,"y":396.0731506347656}],"reprojectionErrors":[{"x":-0.16986083984375,"y":0.046630859375},{"x":-0.0196533203125,"y":-0.028289794921875},{"x":0.25616455078125,"y":-0.0946502685546875},{"x":-0.140655517578125,"y":-0.013031005859375},{"x":-0.1539306640625,"y":-0.2015533447265625},{"x":0.180908203125,"y":0.2139129638671875},{"x":-0.2593994140625,"y":-0.14349365234375},{"x":0.356689453125,"y":0.17767333984375},{"x":-0.0234375,"y":-0.189300537109375},{"x":0.2734375,"y":-0.037750244140625},{"x":0.10577392578125,"y":-0.0185394287109375},{"x":0.0684814453125,"y":-0.1203765869140625},{"x":0.00787353515625,"y":-0.030548095703125},{"x":0.19549560546875,"y":-0.0479888916015625},{"x":0.117828369140625,"y":-0.305023193359375},{"x":0.2806396484375,"y":-0.15936279296875},{"x":0.18231201171875,"y":-0.236328125},{"x":0.0274658203125,"y":-0.190399169921875},{"x":0.0499267578125,"y":-0.173736572265625},{"x":0.18548583984375,"y":-0.03875732421875},{"x":0.06109619140625,"y":0.04583740234375},{"x":0.2406005859375,"y":0.263580322265625},{"x":0.144287109375,"y":0.241546630859375},{"x":0.1627197265625,"y":0.309967041015625},{"x":0.338134765625,"y":0.200225830078125},{"x":-0.0172119140625,"y":0.253509521484375},{"x":0.2236328125,"y":0.350189208984375},{"x":0.1287841796875,"y":-0.09710693359375},{"x":0.03656005859375,"y":-0.013092041015625},{"x":0.313507080078125,"y":-0.142608642578125},{"x":0.04229736328125,"y":-0.061737060546875},{"x":0.11529541015625,"y":-0.043548583984375},{"x":0.11431884765625,"y":0.0325927734375},{"x":-0.0379638671875,"y":0.015380859375},{"x":0.026123046875,"y":-0.048980712890625},{"x":0.119293212890625,"y":0.069580078125},{"x":0.146820068359375,"y":0.105987548828125},{"x":0.03643798828125,"y":0.131744384765625},{"x":0.17047119140625,"y":0.18133544921875},{"x":-0.164794921875,"y":-0.053680419921875},{"x":-0.2545166015625,"y":-0.064178466796875}],"optimisedCameraToObject":{"translation":{"x":0.03245560578291374,"y":-0.11448533298953378,"z":0.49154189789336694},"rotation":{"quaternion":{"W":0.9996548030252677,"X":0.005596337866809827,"Y":-0.003718129262452472,"Z":0.02539943514689826}}},"includeObservationInCalibration":true,"snapshotName":"img26.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img26.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.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.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":465.79461669921875,"y":194.57469177246094},{"x":500.9768371582031,"y":197.2300262451172},{"x":535.7828979492188,"y":199.96719360351562},{"x":570.7738037109375,"y":202.45094299316406},{"x":605.1046142578125,"y":205.14010620117188},{"x":427.94805908203125,"y":227.7534637451172},{"x":462.7135925292969,"y":230.26995849609375},{"x":498.13446044921875,"y":232.8081817626953},{"x":532.9523315429688,"y":235.29562377929688},{"x":567.8305053710938,"y":237.89820861816406},{"x":601.9569091796875,"y":240.29925537109375},{"x":389.8349914550781,"y":260.6741638183594},{"x":424.863037109375,"y":263.0618896484375},{"x":460.031982421875,"y":265.7435607910156},{"x":494.95513916015625,"y":268.2080078125},{"x":529.8604125976562,"y":270.570068359375},{"x":387.09405517578125,"y":296.1213073730469},{"x":422.1976623535156,"y":298.72918701171875},{"x":457.18328857421875,"y":301.1380920410156},{"x":492.13519287109375,"y":303.6350402832031},{"x":527.0037231445312,"y":305.9007873535156},{"x":384.38800048828125,"y":331.2514343261719},{"x":419.47210693359375,"y":333.2155456542969},{"x":454.5055236816406,"y":335.83587646484375},{"x":489.3376770019531,"y":338.0233154296875},{"x":524.1068115234375,"y":340.41290283203125},{"x":558.6611938476562,"y":342.6106262207031},{"x":593.001953125,"y":345.28448486328125},{"x":381.8795471191406,"y":366.25732421875},{"x":416.95965576171875,"y":368.64910888671875},{"x":451.68890380859375,"y":370.8818664550781},{"x":486.6841735839844,"y":373.0665283203125},{"x":520.9815673828125,"y":375.2961730957031},{"x":555.8981323242188,"y":377.72418212890625},{"x":590.01171875,"y":380.08001708984375},{"x":379.280029296875,"y":401.224365234375},{"x":414.2626037597656,"y":403.2995910644531},{"x":449.23895263671875,"y":405.67047119140625},{"x":483.8260498046875,"y":407.76580810546875},{"x":518.4837036132812,"y":410.06036376953125},{"x":552.9310913085938,"y":412.3166809082031},{"x":587.213623046875,"y":414.57635498046875}],"reprojectionErrors":[{"x":-0.150299072265625,"y":-0.0428466796875},{"x":-0.14776611328125,"y":-0.0226287841796875},{"x":0.0731201171875,"y":-0.0906524658203125},{"x":-0.05548095703125,"y":0.0877685546875},{"x":0.3048095703125,"y":0.0532379150390625},{"x":-0.31622314453125,"y":-0.1902923583984375},{"x":0.1729736328125,"y":-0.1023406982421875},{"x":-0.1431884765625,"y":-0.0443267822265625},{"x":-0.01324462890625,"y":0.0557861328125},{"x":-0.10723876953125,"y":0.0315093994140625},{"x":0.3802490234375,"y":0.19903564453125},{"x":-0.1851806640625,"y":-0.110565185546875},{"x":0.10137939453125,"y":0.03973388671875},{"x":0.104888916015625,"y":-0.1138916015625},{"x":0.205108642578125,"y":-0.060791015625},{"x":0.167236328125,"y":0.083740234375},{"x":-0.01763916015625,"y":-0.1239013671875},{"x":0.10894775390625,"y":-0.2672119140625},{"x":0.2122802734375,"y":-0.223846435546875},{"x":0.201171875,"y":-0.28131103515625},{"x":0.118408203125,"y":-0.120758056640625},{"x":0.126251220703125,"y":-0.002593994140625},{"x":0.186676025390625,"y":0.42498779296875},{"x":0.157470703125,"y":0.181793212890625},{"x":0.182220458984375,"y":0.3564453125},{"x":0.115966796875,"y":0.313507080078125},{"x":0.10369873046875,"y":0.446563720703125},{"x":0.13775634765625,"y":0.08721923828125},{"x":0.08404541015625,"y":0.0570068359375},{"x":0.06158447265625,"y":-0.015350341796875},{"x":0.250518798828125,"y":0.05450439453125},{"x":0.027099609375,"y":0.155181884765625},{"x":0.34844970703125,"y":0.1932373046875},{"x":-0.109130859375,"y":0.014923095703125},{"x":0.0699462890625,"y":-0.109649658203125},{"x":0.144683837890625,"y":-0.0340576171875},{"x":0.13165283203125,"y":0.138519287109375},{"x":-0.01373291015625,"y":-0.003631591796875},{"x":0.084716796875,"y":0.110321044921875},{"x":-0.03948974609375,"y":0.005218505859375},{"x":-0.11224365234375,"y":-0.081817626953125},{"x":-0.1854248046875,"y":-0.1927490234375}],"optimisedCameraToObject":{"translation":{"x":-0.007154790224406726,"y":-0.10307650220735307,"z":0.48521603743761177},"rotation":{"quaternion":{"W":0.9988833122335768,"X":0.02516842088777473,"Y":-0.018893106519572517,"Z":0.03523818464868207}}},"includeObservationInCalibration":true,"snapshotName":"img27.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img27.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.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":405.9717712402344,"y":312.1780700683594},{"x":440.0703430175781,"y":314.48394775390625},{"x":473.9410705566406,"y":316.65850830078125},{"x":507.50042724609375,"y":319.07305908203125},{"x":541.0534057617188,"y":321.5313415527344},{"x":335.9266052246094,"y":340.1058044433594},{"x":369.7655029296875,"y":342.3905944824219},{"x":403.8347473144531,"y":345.3943176269531},{"x":436.9797668457031,"y":347.1905517578125},{"x":470.2457275390625,"y":349.2221984863281},{"x":503.8778076171875,"y":351.8309020996094},{"x":536.8812255859375,"y":353.7036437988281},{"x":333.94061279296875,"y":372.3429870605469},{"x":367.0425720214844,"y":374.1631164550781},{"x":400.9522399902344,"y":376.58343505859375},{"x":433.7161560058594,"y":378.8739013671875},{"x":467.01068115234375,"y":381.377197265625},{"x":500.1578369140625,"y":383.566650390625},{"x":533.0794067382812,"y":385.859619140625},{"x":332.0982971191406,"y":403.976318359375},{"x":365.041748046875,"y":405.9576416015625},{"x":397.90386962890625,"y":408.5167541503906},{"x":430.8712463378906,"y":410.776611328125},{"x":463.5533447265625,"y":412.755615234375},{"x":496.89251708984375,"y":415.02545166015625},{"x":529.2699584960938,"y":417.4015808105469},{"x":330.1229248046875,"y":434.2522277832031},{"x":362.68280029296875,"y":436.4964599609375},{"x":395.08074951171875,"y":438.74853515625},{"x":428.11334228515625,"y":441.34747314453125},{"x":460.5318298339844,"y":443.1285705566406},{"x":492.90771484375,"y":445.2727355957031},{"x":525.2457275390625,"y":447.72918701171875},{"x":327.9172668457031,"y":464.5654296875},{"x":360.35906982421875,"y":467.0973815917969},{"x":392.7766418457031,"y":469.15380859375},{"x":425.1654052734375,"y":471.1559143066406},{"x":457.15814208984375,"y":473.3932800292969},{"x":489.4927062988281,"y":476.0495910644531},{"x":521.605712890625,"y":477.9019470214844},{"x":326.2951965332031,"y":493.98223876953125},{"x":358.2611389160156,"y":496.1531982421875},{"x":390.130126953125,"y":498.84393310546875},{"x":422.29498291015625,"y":500.98736572265625},{"x":454.16552734375,"y":503.0650634765625},{"x":486.048583984375,"y":505.3249206542969},{"x":517.9661865234375,"y":507.81341552734375}],"reprojectionErrors":[{"x":0.0643310546875,"y":-0.10455322265625},{"x":-0.120819091796875,"y":-0.01263427734375},{"x":-0.120880126953125,"y":0.196441650390625},{"x":0.140716552734375,"y":0.15081787109375},{"x":0.3519287109375,"y":0.04632568359375},{"x":0.120880126953125,"y":-0.040252685546875},{"x":-0.085052490234375,"y":0.062469482421875},{"x":-0.5491943359375,"y":-0.569122314453125},{"x":-0.1239013671875,"y":-0.009033203125},{"x":0.13873291015625,"y":0.29937744140625},{"x":-0.0133056640625,"y":0.014007568359375},{"x":0.40789794921875,"y":0.4473876953125},{"x":0.088348388671875,"y":-0.120025634765625},{"x":0.28009033203125,"y":0.41094970703125},{"x":-0.363006591796875,"y":0.324371337890625},{"x":0.105682373046875,"y":0.349822998046875},{"x":0.003082275390625,"y":0.1441650390625},{"x":4.2724609375E-4,"y":0.233673095703125},{"x":0.169189453125,"y":0.200531005859375},{"x":-0.0455322265625,"y":-0.2509765625},{"x":-0.02923583984375,"y":0.083251953125},{"x":0.041961669921875,"y":-0.1795654296875},{"x":-0.025177001953125,"y":-0.162872314453125},{"x":0.15325927734375,"y":0.114501953125},{"x":-0.37176513671875,"y":0.080474853515625},{"x":0.01202392578125,"y":-0.08087158203125},{"x":-0.005096435546875,"y":0.3359375},{"x":0.066070556640625,"y":0.372589111328125},{"x":0.2734375,"y":0.380279541015625},{"x":-0.186126708984375,"y":0.01953125},{"x":-0.07037353515625,"y":0.45465087890625},{"x":0.042724609375,"y":0.504302978515625},{"x":0.1419677734375,"y":0.2188720703125},{"x":0.305908203125,"y":0.26104736328125},{"x":0.17156982421875,"y":-0.023834228515625},{"x":0.036376953125,"y":0.14385986328125},{"x":-0.10150146484375,"y":0.34259033203125},{"x":0.118804931640625,"y":0.28228759765625},{"x":-0.046966552734375,"y":-0.221038818359375},{"x":-0.04168701171875,"y":0.0550537109375},{"x":0.07269287109375,"y":0.472686767578125},{"x":0.09564208984375,"y":0.515716552734375},{"x":0.191070556640625,"y":0.014373779296875},{"x":-0.040069580078125,"y":0.03533935546875},{"x":-0.01385498046875,"y":0.09661865234375},{"x":-0.043365478515625,"y":-0.050018310546875},{"x":-0.15679931640625,"y":-0.45147705078125}],"optimisedCameraToObject":{"translation":{"x":-0.04867072340088375,"y":-0.01832101838619833,"z":0.5053021167898529},"rotation":{"quaternion":{"W":0.9938371689272831,"X":0.10492779849425388,"Y":-0.001581974226781419,"Z":0.03571184844415032}}},"includeObservationInCalibration":true,"snapshotName":"img28.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img28.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":293.9643249511719,"y":379.8685302734375},{"x":326.1309509277344,"y":382.9114685058594},{"x":359.0419616699219,"y":386.30755615234375},{"x":391.7657165527344,"y":389.3065185546875},{"x":423.96441650390625,"y":392.71441650390625},{"x":456.6072692871094,"y":395.2980041503906},{"x":488.8177185058594,"y":398.8053894042969},{"x":291.1709289550781,"y":409.4529724121094},{"x":323.42169189453125,"y":413.0541687011719},{"x":355.9486083984375,"y":416.02252197265625},{"x":388.4119873046875,"y":419.1802062988281},{"x":419.7155456542969,"y":422.2720031738281},{"x":452.0560607910156,"y":425.2830810546875},{"x":483.7285461425781,"y":427.8988952636719},{"x":289.5106506347656,"y":438.3467712402344},{"x":320.8888244628906,"y":441.2348327636719},{"x":353.2174072265625,"y":444.31396484375},{"x":384.4458923339844,"y":447.1912536621094},{"x":415.91143798828125,"y":450.8494567871094},{"x":447.78594970703125,"y":453.34197998046875},{"x":478.94219970703125,"y":456.8750305175781},{"x":286.9893798828125,"y":466.89410400390625},{"x":318.2755432128906,"y":469.7911682128906},{"x":349.7681579589844,"y":472.8266296386719},{"x":381.0450134277344,"y":475.916015625},{"x":412.5104675292969,"y":478.4594421386719},{"x":443.8511962890625,"y":481.65386962890625},{"x":474.48040771484375,"y":484.1413879394531},{"x":285.24212646484375,"y":493.8400573730469},{"x":315.98162841796875,"y":496.9057922363281},{"x":346.90399169921875,"y":499.9557189941406},{"x":378.2687683105469,"y":502.46466064453125},{"x":408.74896240234375,"y":505.69659423828125},{"x":439.8577575683594,"y":508.07867431640625},{"x":469.9589538574219,"y":511.5660705566406},{"x":282.67169189453125,"y":520.44140625},{"x":314.0028991699219,"y":523.6378784179688},{"x":344.0594787597656,"y":526.4285278320312},{"x":374.728271484375,"y":529.2548828125},{"x":404.8978271484375,"y":532.0230712890625},{"x":436.1986999511719,"y":534.8216552734375},{"x":466.1737976074219,"y":538.3458251953125},{"x":281.0627136230469,"y":546.8153686523438},{"x":311.26043701171875,"y":549.5764770507812},{"x":341.60009765625,"y":552.7264404296875},{"x":371.8474426269531,"y":555.7198486328125},{"x":401.7217102050781,"y":557.9270629882812},{"x":431.73187255859375,"y":560.9755249023438},{"x":461.5691223144531,"y":564.0104370117188}],"reprojectionErrors":[{"x":-0.369415283203125,"y":-0.0040283203125},{"x":0.1552734375,"y":0.186004638671875},{"x":-0.116485595703125,"y":-0.00189208984375},{"x":-0.259368896484375,"y":0.18194580078125},{"x":0.058197021484375,"y":-0.06903076171875},{"x":-0.1392822265625,"y":0.477813720703125},{"x":0.0186767578125,"y":0.073883056640625},{"x":0.20086669921875,"y":0.184478759765625},{"x":0.202972412109375,"y":-0.251251220703125},{"x":-0.121551513671875,"y":-0.0804443359375},{"x":-0.4390869140625,"y":-0.125762939453125},{"x":0.340484619140625,"y":-0.132568359375},{"x":0.014373779296875,"y":-0.086517333984375},{"x":0.281494140625,"y":0.326385498046875},{"x":-0.299163818359375,"y":0.25750732421875},{"x":0.147369384765625,"y":0.46966552734375},{"x":-0.4053955078125,"y":0.463104248046875},{"x":0.087066650390625,"y":0.630157470703125},{"x":0.2816162109375,"y":-0.01239013671875},{"x":4.8828125E-4,"y":0.481536865234375},{"x":0.365020751953125,"y":-0.094757080078125},{"x":0.12237548828125,"y":-0.100921630859375},{"x":0.24273681640625,"y":0.03924560546875},{"x":0.109222412109375,"y":0.011993408203125},{"x":0.138214111328125,"y":-0.0986328125},{"x":-0.080413818359375,"y":0.30670166015625},{"x":-0.239105224609375,"y":0.03057861328125},{"x":0.24322509765625,"y":0.43048095703125},{"x":-0.171600341796875,"y":0.391204833984375},{"x":0.086822509765625,"y":0.301788330078125},{"x":0.11639404296875,"y":0.19793701171875},{"x":-0.34814453125,"y":0.6043701171875},{"x":0.0146484375,"y":0.256622314453125},{"x":-0.314117431640625,"y":0.727142333984375},{"x":0.296234130859375,"y":0.060272216796875},{"x":0.4140625,"y":0.50286865234375},{"x":-0.31854248046875,"y":0.22381591796875},{"x":0.178863525390625,"y":0.31915283203125},{"x":0.013916015625,"y":0.34698486328125},{"x":0.29254150390625,"y":0.400634765625},{"x":-0.621246337890625,"y":0.3912353515625},{"x":-0.27581787109375,"y":-0.37689208984375},{"x":0.092803955078125,"y":0.1414794921875},{"x":0.10333251953125,"y":0.2408447265625},{"x":-0.071380615234375,"y":-0.0811767578125},{"x":-0.202423095703125,"y":-0.27960205078125},{"x":-0.01446533203125,"y":0.27490234375},{"x":-0.021759033203125,"y":-0.045654296875},{"x":0.07916259765625,"y":-0.38677978515625}],"optimisedCameraToObject":{"translation":{"x":-0.08323945884560988,"y":0.037952487497259275,"z":0.5223705566148297},"rotation":{"quaternion":{"W":0.9880823354844781,"X":0.1452679174364017,"Y":-0.002552702990465036,"Z":0.05083319953212273}}},"includeObservationInCalibration":true,"snapshotName":"img29.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img29.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.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.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}],"locationInImageSpace":[{"x":288.7093200683594,"y":405.2923889160156},{"x":321.8953857421875,"y":407.308837890625},{"x":354.2223815917969,"y":409.8620910644531},{"x":387.0834045410156,"y":411.7196350097656},{"x":419.14068603515625,"y":414.048828125},{"x":255.7470703125,"y":432.5801086425781},{"x":288.0283203125,"y":435.0072326660156},{"x":320.53790283203125,"y":437.1368713378906},{"x":352.4447021484375,"y":439.76971435546875},{"x":384.74853515625,"y":441.60687255859375},{"x":417.1012268066406,"y":443.6098937988281},{"x":223.14451599121094,"y":459.6646423339844},{"x":254.5936279296875,"y":461.3688049316406},{"x":287.2936096191406,"y":463.8106384277344},{"x":318.9393615722656,"y":465.9602966308594},{"x":350.30810546875,"y":468.5065002441406},{"x":382.5262451171875,"y":470.4820556640625},{"x":413.53948974609375,"y":472.8867492675781},{"x":222.85873413085938,"y":487.38092041015625},{"x":254.62384033203125,"y":489.91339111328125},{"x":285.91961669921875,"y":492.1321105957031},{"x":317.6078186035156,"y":494.7411804199219},{"x":348.7239074707031,"y":496.8511657714844},{"x":380.76287841796875,"y":499.033935546875},{"x":411.5990295410156,"y":501.11663818359375},{"x":223.03248596191406,"y":514.983154296875},{"x":253.81771850585938,"y":517.20361328125},{"x":285.162353515625,"y":519.6964721679688},{"x":316.22930908203125,"y":521.91552734375},{"x":346.8365173339844,"y":524.2481079101562},{"x":377.9671325683594,"y":526.1317749023438},{"x":409.445556640625,"y":528.7875366210938},{"x":222.24493408203125,"y":541.6229248046875},{"x":252.81588745117188,"y":544.4747314453125},{"x":345.16265869140625,"y":551.1740112304688},{"x":376.01214599609375,"y":553.7467651367188},{"x":406.6285705566406,"y":556.26025390625},{"x":222.1927947998047,"y":568.5065307617188},{"x":252.18162536621094,"y":570.391357421875}],"reprojectionErrors":[{"x":0.27117919921875,"y":-0.1263427734375},{"x":-0.264129638671875,"y":0.199737548828125},{"x":0.083770751953125,"y":-0.029510498046875},{"x":-0.084716796875,"y":0.41796875},{"x":0.5616455078125,"y":0.374359130859375},{"x":-0.079376220703125,"y":0.0364990234375},{"x":-0.14776611328125,"y":-0.04779052734375},{"x":-0.41448974609375,"y":0.1456298828125},{"x":-0.054779052734375,"y":-0.184356689453125},{"x":-0.074737548828125,"y":0.2606201171875},{"x":-0.132568359375,"y":0.5185546875},{"x":0.0744781494140625,"y":-0.33221435546875},{"x":0.4040985107421875,"y":0.3096923828125},{"x":-0.481597900390625,"y":0.19305419921875},{"x":-0.28369140625,"y":0.347137451171875},{"x":0.2144775390625,"y":0.082855224609375},{"x":-0.119659423828125,"y":0.366851806640625},{"x":0.761962890625,"y":0.198944091796875},{"x":0.1016082763671875,"y":0.3040771484375},{"x":-0.274169921875,"y":0.1016845703125},{"x":-0.14581298828125,"y":0.1905517578125},{"x":-0.38104248046875,"y":-0.1339111328125},{"x":-0.02130126953125,"y":0.01727294921875},{"x":-0.56768798828125,"y":0.07183837890625},{"x":0.099517822265625,"y":0.202117919921875},{"x":-0.317779541015625,"y":0.35205078125},{"x":-0.0949249267578125,"y":0.44561767578125},{"x":-0.3973388671875,"y":0.2427978515625},{"x":-0.393798828125,"y":0.28936767578125},{"x":0.091888427734375,"y":0.19744873046875},{"x":0.07073974609375,"y":0.5291748046875},{"x":-0.28759765625,"y":0.06304931640625},{"x":0.2367095947265625,"y":0.6820068359375},{"x":0.300537109375,"y":0.128173828125},{"x":0.035980224609375,"y":0.168701171875},{"x":-0.079254150390625,"y":-0.2103271484375},{"x":0.04913330078125,"y":-0.55718994140625},{"x":0.06793212890625,"y":0.10870361328125},{"x":0.3482818603515625,"y":0.505859375}],"optimisedCameraToObject":{"translation":{"x":-0.13858952939981845,"y":0.05462210397925629,"z":0.5252639846479085},"rotation":{"quaternion":{"W":0.9903458037998749,"X":0.1340354263735569,"Y":0.008170477058724467,"Z":0.03439384650589897}}},"includeObservationInCalibration":true,"snapshotName":"img30.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/52e3bd0e-b8ca-4edb-88fd-c60ae44bd6fc/imgs/800x600/img30.png"}],"calobjectSize":{"width":7.0,"height":7.0},"calobjectSpacing":0.0254,"lensmodel":"LENSMODEL_OPENCV"} \ No newline at end of file diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 019d915..e656cea 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -28,31 +28,18 @@ public static enum Mode { } public static final class VisionConstants { - public static final String LEFT_CAMERA_NAME = "left_arducam"; - public static final String RIGHT_CAMERA_NAME = "right_arducam"; + public static final String CAMERA_NAME = "left_arducam"; - public static final Transform3d FRONT_LEFT_TRANSFORM = + public static final Transform3d CAMERA_TRANSFORM = new Transform3d( new Translation3d( - Units.inchesToMeters(6.2944), - Units.inchesToMeters(8.9822), - Units.inchesToMeters(12.125)), - new Rotation3d(0, 0.0, Units.degreesToRadians(-35))); - - public static final Transform3d FRONT_RIGHT_TRANSFORM = - new Transform3d( - new Translation3d( - Units.inchesToMeters(6.2944), - Units.inchesToMeters(-8.9822), - Units.inchesToMeters(12.125)), - new Rotation3d(0, 0.0, Units.degreesToRadians(35))); + Units.inchesToMeters(7.883 + 0.5), + Units.inchesToMeters(-10.895 - 0.5), + Units.inchesToMeters(8)), + new Rotation3d(0, Units.degreesToRadians(-22.0), Units.degreesToRadians(90 - 61.475))); public static final CameraParameters LEFT_PARAMETERS = - CameraParameters.loadFromName(LEFT_CAMERA_NAME, 800, 600) - .withTransform(FRONT_LEFT_TRANSFORM); - public static final CameraParameters RIGHT_PARAMETERS = - CameraParameters.loadFromName(RIGHT_CAMERA_NAME, 800, 600) - .withTransform(FRONT_RIGHT_TRANSFORM); + CameraParameters.loadFromName(CAMERA_NAME, 800, 600).withTransform(CAMERA_TRANSFORM); // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index 56fc0c6..66dbd98 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -169,7 +169,9 @@ public void disabledInit() {} public void disabledPeriodic() {} @Override - public void disabledExit() {} + public void disabledExit() { + robotContainer.getDrive().calculateVisionHeadingOffset(); + } @Override public void autonomousInit() { diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 1a53f99..01c0bb0 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -69,10 +69,6 @@ public RobotContainer() { new Vision( drive::addVisionMeasurement, drive::getTimestampedHeading, - new VisionIOPhoton( - VisionConstants.RIGHT_PARAMETERS, - PoseStrategy.CONSTRAINED_SOLVEPNP, - PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR), new VisionIOPhoton( VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, @@ -97,11 +93,6 @@ public RobotContainer() { VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, - drive::getRawOdometryPose), - new VisionIOSim( - VisionConstants.RIGHT_PARAMETERS, - PoseStrategy.CONSTRAINED_SOLVEPNP, - PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, drive::getRawOdometryPose)); break; @@ -129,9 +120,10 @@ public RobotContainer() { autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); autoChooser.get(); - SmartDashboard.putData( - "Calculate Vision Heading Offset", - Commands.runOnce(() -> drive.calculateVisionHeadingOffset())); + // SmartDashboard.putData( + // "Calculate Vision Heading Offset", + // Commands.runOnce(() -> drive.calculateVisionHeadingOffset()) + // .alongWith(Commands.print("offset calculated"))); if (Constants.TUNING) setupDevelopmentRoutines(); diff --git a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java index 3183f07..70490e2 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/VisionIOPhoton.java @@ -39,7 +39,6 @@ public class VisionIOPhoton implements VisionIO { public static final Optional CONSTRAINED_SOLVEPNP_PARAMETERS = Optional.of(new ConstrainedSolvepnpParams(false, 0.5)); - // TODO: AllianceUtils /** * Creates a new VisionIOPhotonVision. * diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib-2026.1.2.json similarity index 87% rename from vendordeps/PathplannerLib.json rename to vendordeps/PathplannerLib-2026.1.2.json index 2a55642..5f04ffa 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib-2026.1.2.json @@ -1,7 +1,7 @@ { - "fileName": "PathplannerLib.json", + "fileName": "PathplannerLib-2026.1.2.json", "name": "PathplannerLib", - "version": "2025.2.7", + "version": "2026.1.2", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2026", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.2.7" + "version": "2026.1.2" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.2.7", + "version": "2026.1.2", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 082b01d..bb613bf 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2026.0.0", + "version": "2026.0.1", "frcYear": "2026", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2026.0.0" + "version": "2026.0.1" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.0", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -34,7 +34,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.0", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -49,7 +49,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.0", + "version": "2026.0.1", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -66,7 +66,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2026.0.0", + "version": "2026.0.1", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -83,7 +83,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2026.0.0", + "version": "2026.0.1", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, @@ -100,7 +100,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibBackendDriver", - "version": "2026.0.0", + "version": "2026.0.1", "libName": "BackendDriver", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -116,7 +116,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "RevLibWpiBackendDriver", - "version": "2026.0.0", + "version": "2026.0.1", "libName": "REVLibWpi", "sharedLibrary": true, "skipInvalidPlatforms": true, diff --git a/vendordeps/ReduxLib-2026.0.0-beta1.json b/vendordeps/ReduxLib-2026.1.1.json similarity index 87% rename from vendordeps/ReduxLib-2026.0.0-beta1.json rename to vendordeps/ReduxLib-2026.1.1.json index 0a08300..9081f8b 100644 --- a/vendordeps/ReduxLib-2026.0.0-beta1.json +++ b/vendordeps/ReduxLib-2026.1.1.json @@ -1,7 +1,7 @@ { - "fileName": "ReduxLib-2026.0.0-beta1.json", + "fileName": "ReduxLib-2026.1.1.json", "name": "ReduxLib", - "version": "2026.0.0-beta1", + "version": "2026.1.1", "frcYear": "2026", "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", "mavenUrls": [ @@ -12,14 +12,14 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-java", - "version": "2026.0.0-beta1" + "version": "2026.1.1" } ], "jniDependencies": [ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-fifo", - "version": "2026.0.0-beta1", + "version": "2026.1.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -35,7 +35,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-cpp", - "version": "2026.0.0-beta1", + "version": "2026.1.1", "libName": "ReduxLib", "headerClassifier": "headers", "sourcesClassifier": "sources", @@ -52,7 +52,7 @@ { "groupId": "com.reduxrobotics.frc", "artifactId": "ReduxLib-fifo", - "version": "2026.0.0-beta1", + "version": "2026.1.1", "libName": "reduxfifo", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index 8b1d42b..7508481 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-3", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2026", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-3", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-3", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2026.0.1-beta", + "version": "v2026.1.1-rc-3", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2026.0.1-beta" + "version": "v2026.1.1-rc-3" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2026.0.1-beta" + "version": "v2026.1.1-rc-3" } ] } From 4763aa61b3ff861ca101d42b53f64dd50c185fbd Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Wed, 21 Jan 2026 10:56:44 -0500 Subject: [PATCH 7/7] fixed vision offset command --- src/main/java/org/team2342/frc/Constants.java | 2 +- src/main/java/org/team2342/frc/Robot.java | 4 +--- src/main/java/org/team2342/frc/RobotContainer.java | 9 +++++---- .../java/org/team2342/lib/util/CameraParameters.java | 4 +++- 4 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index e656cea..6c95a36 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -13,7 +13,7 @@ import org.team2342.lib.util.CameraParameters; public final class Constants { - public static final Mode CURRENT_MODE = Mode.REAL; + public static final Mode CURRENT_MODE = Mode.SIM; public static final boolean TUNING = true; public static enum Mode { diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index 66dbd98..56fc0c6 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -169,9 +169,7 @@ public void disabledInit() {} public void disabledPeriodic() {} @Override - public void disabledExit() { - robotContainer.getDrive().calculateVisionHeadingOffset(); - } + public void disabledExit() {} @Override public void autonomousInit() { diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 01c0bb0..bc96c39 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -120,10 +120,11 @@ public RobotContainer() { autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); autoChooser.get(); - // SmartDashboard.putData( - // "Calculate Vision Heading Offset", - // Commands.runOnce(() -> drive.calculateVisionHeadingOffset()) - // .alongWith(Commands.print("offset calculated"))); + SmartDashboard.putData( + "Calculate Vision Heading Offset", + Commands.runOnce(() -> drive.calculateVisionHeadingOffset()) + .alongWith(Commands.print("Calculated Vision Offset")) + .ignoringDisable(true)); if (Constants.TUNING) setupDevelopmentRoutines(); diff --git a/src/main/java/org/team2342/lib/util/CameraParameters.java b/src/main/java/org/team2342/lib/util/CameraParameters.java index dde8f0b..dcbc312 100644 --- a/src/main/java/org/team2342/lib/util/CameraParameters.java +++ b/src/main/java/org/team2342/lib/util/CameraParameters.java @@ -42,7 +42,8 @@ public CameraParameters( double avgErrorPx, double errorStdDevPx, Matrix cameraMatrix, - Matrix distCoeffs) { + Matrix distCoeffs, + Transform3d transform) { this.cameraName = cameraName; this.resWidth = resWidth; this.resHeight = resHeight; @@ -50,6 +51,7 @@ public CameraParameters( this.errorStdDevPx = errorStdDevPx; this.cameraMatrix = cameraMatrix; this.distCoeffs = distCoeffs; + this.transform = transform; } public CameraParameters(String cameraName, int resWidth, int resHeight) {