From 2e1a23b2a5110b85fcaa655345418f191f48bcd1 Mon Sep 17 00:00:00 2001 From: aniruddhsridhar Date: Sat, 31 Jan 2026 15:08:19 -0500 Subject: [PATCH 01/15] intake-pivot Creates an intake-pivot branch and a pivot file inside of it. The file controls the angle of the intake using the new SmartMotorIO type. It also adds pivot constants to the Constants.java file --- src/main/java/org/team2342/frc/Constants.java | 24 ++++++++ .../team2342/frc/subsystems/pivot/Pivot.java | 55 +++++++++++++++++++ 2 files changed, 79 insertions(+) create mode 100644 src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index d748e34..548e619 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -9,9 +9,15 @@ 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.trajectory.TrapezoidProfile; import edu.wpi.first.math.util.Units; + +import org.team2342.lib.motors.smart.SmartMotorConfig; import org.team2342.lib.util.CameraParameters; +import com.revrobotics.spark.SparkBase.ControlType; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; + public final class Constants { public static final Mode CURRENT_MODE = Mode.REAL; public static final boolean TUNING = true; @@ -114,4 +120,22 @@ public static final class CANConstants { public static final int PDH_ID = 62; } + public static final class PivotConstants { + public static final double GEAR_RATIO = 45; + public static final double CLAW_LENGTH = Units.inchesToMeters(16.6); + public static final double MIN_ANGLE = -0.93; + public static final double MAX_ANGLE = 1.43; + public static final double CUTOFF_ANGLE = 1.2; + public static final double MOVE_ANGLE = 0.5; + public static final double AT_TARGET_TOLERANCE = 0.01; + + public static final SmartMotorConfig PIVOT_CONFIG = + new SmartMotorConfig() + .withGearRatio(GEAR_RATIO) + .withIdleMode(org.team2342.lib.motors.MotorConfig.IdleMode.BRAKE) + .withProfileConstraintsRad(new TrapezoidProfile.Constraints(Units.degreesToRadians(1260), Units.degreesToRadians(1080))) + .withControlType(org.team2342.lib.motors.smart.SmartMotorConfig.ControlType.PROFILED_POSITION) + .withSupplyCurrentLimit(40); + + } } diff --git a/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java b/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java new file mode 100644 index 0000000..822c243 --- /dev/null +++ b/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java @@ -0,0 +1,55 @@ +package org.team2342.frc.subsystems.pivot; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj2.command.Command; +import org.littletonrobotics.junction.Logger; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.team2342.lib.motors.smart.SmartMotorIO; +import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; + +public class Pivot extends SubsystemBase { + + private final SmartMotorIO pivotMotor; + private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); + + public Pivot(SmartMotorIO pivotMotor) { + this.pivotMotor = pivotMotor; + setName("Pivot"); + setDefaultCommand(run(() -> pivotMotor.runVoltage(0.0))); + + @Override + public void periodic() { + pivotMotor.updateInputs(pivotMotorInputs); + Logger.processInputs("Pivot/pivotMotor", pivotMotorInputs); + } + public Rotation2d getAngle() { + return Rotation2d.fromRadians(pivotMotorInputs.positionRad / PivotConstants.GEAR_RATIO); + } + + public Command goToAngle(Rotation2d targetAngle) { + return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) + .until(() -> { + // Using minus() and getRadians() handles the wrap-around math for you! + double error = targetAngle.minus(getAngle()).getRadians(); + return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; + }) + .withName("Wrist Go To Angle"); // Fixed the quote here + } + + public Command holdAngle(Rotation2d targetAngle) { + return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Wrist Hold Angle"); + } + + public Command shoot(double metersPerSec) { + double radPerSec = metersPerSec / PivotConstants.WHEEL_RADIUS_METERS; + return run(() -> pivotMotor.runVelocity(radPerSec)).withName("Run Pivot"); + } + + public Command stop() { + return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Stop"); + } + + public double getVelocityMetersPerSec() { + return pivotMotorInputs.velocityRadPerSec * PivotConstants.WHEEL_RADIUS_METERS; + } +} + From 3efa0ad30dfff5db8a9ff82ac7973339283ad1d8 Mon Sep 17 00:00:00 2001 From: aniruddhsridhar Date: Sat, 31 Jan 2026 15:41:27 -0500 Subject: [PATCH 02/15] Pivot code Pivot code --- src/main/java/org/team2342/frc/Constants.java | 12 +++++------ .../team2342/frc/subsystems/pivot/Pivot.java | 20 ++++++++----------- 2 files changed, 13 insertions(+), 19 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 548e619..5eaa5b6 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -14,10 +14,8 @@ import org.team2342.lib.motors.smart.SmartMotorConfig; import org.team2342.lib.util.CameraParameters; - -import com.revrobotics.spark.SparkBase.ControlType; -import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; - +import org.team2342.lib.motors.MotorConfig.IdleMode; +import org.team2342.lib.motors.smart.SmartMotorConfig.ControlType; public final class Constants { public static final Mode CURRENT_MODE = Mode.REAL; public static final boolean TUNING = true; @@ -121,7 +119,7 @@ public static final class CANConstants { public static final int PDH_ID = 62; } public static final class PivotConstants { - public static final double GEAR_RATIO = 45; + public static final double GEAR_RATIO = 9; public static final double CLAW_LENGTH = Units.inchesToMeters(16.6); public static final double MIN_ANGLE = -0.93; public static final double MAX_ANGLE = 1.43; @@ -132,9 +130,9 @@ public static final class PivotConstants { public static final SmartMotorConfig PIVOT_CONFIG = new SmartMotorConfig() .withGearRatio(GEAR_RATIO) - .withIdleMode(org.team2342.lib.motors.MotorConfig.IdleMode.BRAKE) + .withIdleMode(IdleMode.BRAKE) .withProfileConstraintsRad(new TrapezoidProfile.Constraints(Units.degreesToRadians(1260), Units.degreesToRadians(1080))) - .withControlType(org.team2342.lib.motors.smart.SmartMotorConfig.ControlType.PROFILED_POSITION) + .withControlType(ControlType.PROFILED_POSITION) .withSupplyCurrentLimit(40); } diff --git a/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java b/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java index 822c243..5c7723c 100644 --- a/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java @@ -5,6 +5,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; +import org.team2342.frc.Constants.PivotConstants; public class Pivot extends SubsystemBase { @@ -14,7 +15,8 @@ public class Pivot extends SubsystemBase { public Pivot(SmartMotorIO pivotMotor) { this.pivotMotor = pivotMotor; setName("Pivot"); - setDefaultCommand(run(() -> pivotMotor.runVoltage(0.0))); + final double MIN_ANGLE = -0.93; + setDefaultCommand(run(() -> pivotMotor.runPosition(MIN_ANGLE)));} @Override public void periodic() { @@ -32,24 +34,18 @@ public Command goToAngle(Rotation2d targetAngle) { double error = targetAngle.minus(getAngle()).getRadians(); return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; }) - .withName("Wrist Go To Angle"); // Fixed the quote here + .withName("Pivot Go To Angle"); // Fixed the quote here } public Command holdAngle(Rotation2d targetAngle) { - return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Wrist Hold Angle"); + return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold Angle"); } - public Command shoot(double metersPerSec) { - double radPerSec = metersPerSec / PivotConstants.WHEEL_RADIUS_METERS; - return run(() -> pivotMotor.runVelocity(radPerSec)).withName("Run Pivot"); - } - + public Command stop() { - return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Stop"); + return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Pivot"); } - public double getVelocityMetersPerSec() { - return pivotMotorInputs.velocityRadPerSec * PivotConstants.WHEEL_RADIUS_METERS; - } + } From d8da53ecd7702009278cf6f9cc3f01fc19568231 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Sat, 31 Jan 2026 15:45:00 -0500 Subject: [PATCH 03/15] review --- src/main/java/org/team2342/frc/Constants.java | 2 +- .../frc/subsystems/{pivot => intake}/Pivot.java | 15 ++++++++++----- 2 files changed, 11 insertions(+), 6 deletions(-) rename src/main/java/org/team2342/frc/subsystems/{pivot => intake}/Pivot.java (82%) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 5eaa5b6..8f3372e 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -119,7 +119,7 @@ public static final class CANConstants { public static final int PDH_ID = 62; } public static final class PivotConstants { - public static final double GEAR_RATIO = 9; + public static final double GEAR_RATIO = 27; public static final double CLAW_LENGTH = Units.inchesToMeters(16.6); public static final double MIN_ANGLE = -0.93; public static final double MAX_ANGLE = 1.43; diff --git a/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java similarity index 82% rename from src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java rename to src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 5c7723c..32a4280 100644 --- a/src/main/java/org/team2342/frc/subsystems/pivot/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -1,8 +1,12 @@ -package org.team2342.frc.subsystems.pivot; +package org.team2342.frc.subsystems.intake; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; + +import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; import edu.wpi.first.wpilibj2.command.SubsystemBase; + +import org.team2342.frc.Constants.PivotConstants; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; import org.team2342.frc.Constants.PivotConstants; @@ -15,16 +19,17 @@ public class Pivot extends SubsystemBase { public Pivot(SmartMotorIO pivotMotor) { this.pivotMotor = pivotMotor; setName("Pivot"); - final double MIN_ANGLE = -0.93; - setDefaultCommand(run(() -> pivotMotor.runPosition(MIN_ANGLE)));} + setDefaultCommand(run(() -> pivotMotor.runPosition(PivotConstants.MIN_ANGLE)));} @Override public void periodic() { pivotMotor.updateInputs(pivotMotorInputs); - Logger.processInputs("Pivot/pivotMotor", pivotMotorInputs); + Logger.processInputs("Intake/Pivot", pivotMotorInputs); } + + @AutoLogOutput(key = "Intake/Pivot/Angle") public Rotation2d getAngle() { - return Rotation2d.fromRadians(pivotMotorInputs.positionRad / PivotConstants.GEAR_RATIO); + return Rotation2d.fromRadians(pivotMotorInputs.positionRad); } public Command goToAngle(Rotation2d targetAngle) { From 37a33d9957cd4a80e4459242eee8c45b3749fdba Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Sat, 31 Jan 2026 20:45:47 +0000 Subject: [PATCH 04/15] Auto-format code --- src/main/java/org/team2342/frc/Constants.java | 12 +-- .../team2342/frc/subsystems/intake/Pivot.java | 80 ++++++++++--------- 2 files changed, 48 insertions(+), 44 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 8f3372e..50d6ce6 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -11,11 +11,11 @@ import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.math.util.Units; - -import org.team2342.lib.motors.smart.SmartMotorConfig; -import org.team2342.lib.util.CameraParameters; import org.team2342.lib.motors.MotorConfig.IdleMode; +import org.team2342.lib.motors.smart.SmartMotorConfig; import org.team2342.lib.motors.smart.SmartMotorConfig.ControlType; +import org.team2342.lib.util.CameraParameters; + public final class Constants { public static final Mode CURRENT_MODE = Mode.REAL; public static final boolean TUNING = true; @@ -118,6 +118,7 @@ public static final class CANConstants { public static final int PDH_ID = 62; } + public static final class PivotConstants { public static final double GEAR_RATIO = 27; public static final double CLAW_LENGTH = Units.inchesToMeters(16.6); @@ -131,9 +132,10 @@ public static final class PivotConstants { new SmartMotorConfig() .withGearRatio(GEAR_RATIO) .withIdleMode(IdleMode.BRAKE) - .withProfileConstraintsRad(new TrapezoidProfile.Constraints(Units.degreesToRadians(1260), Units.degreesToRadians(1080))) + .withProfileConstraintsRad( + new TrapezoidProfile.Constraints( + Units.degreesToRadians(1260), Units.degreesToRadians(1080))) .withControlType(ControlType.PROFILED_POSITION) .withSupplyCurrentLimit(40); - } } diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 32a4280..25d371c 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -1,56 +1,58 @@ +// Copyright (c) 2026 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.intake; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; - +import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import edu.wpi.first.wpilibj2.command.SubsystemBase; - import org.team2342.frc.Constants.PivotConstants; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; -import org.team2342.frc.Constants.PivotConstants; public class Pivot extends SubsystemBase { - - private final SmartMotorIO pivotMotor; - private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); - - public Pivot(SmartMotorIO pivotMotor) { - this.pivotMotor = pivotMotor; - setName("Pivot"); - setDefaultCommand(run(() -> pivotMotor.runPosition(PivotConstants.MIN_ANGLE)));} - - @Override - public void periodic() { - pivotMotor.updateInputs(pivotMotorInputs); - Logger.processInputs("Intake/Pivot", pivotMotorInputs); - } - - @AutoLogOutput(key = "Intake/Pivot/Angle") - public Rotation2d getAngle() { - return Rotation2d.fromRadians(pivotMotorInputs.positionRad); + + private final SmartMotorIO pivotMotor; + private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); + + public Pivot(SmartMotorIO pivotMotor) { + this.pivotMotor = pivotMotor; + setName("Pivot"); + setDefaultCommand(run(() -> pivotMotor.runPosition(PivotConstants.MIN_ANGLE))); } - public Command goToAngle(Rotation2d targetAngle) { - return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) - .until(() -> { - // Using minus() and getRadians() handles the wrap-around math for you! - double error = targetAngle.minus(getAngle()).getRadians(); - return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; - }) - .withName("Pivot Go To Angle"); // Fixed the quote here - } + @Override + public void periodic() { + pivotMotor.updateInputs(pivotMotorInputs); + Logger.processInputs("Intake/Pivot", pivotMotorInputs); + } + + @AutoLogOutput(key = "Intake/Pivot/Angle") + public Rotation2d getAngle() { + return Rotation2d.fromRadians(pivotMotorInputs.positionRad); + } - public Command holdAngle(Rotation2d targetAngle) { - return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold Angle"); + public Command goToAngle(Rotation2d targetAngle) { + return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) + .until( + () -> { + // Using minus() and getRadians() handles the wrap-around math for you! + double error = targetAngle.minus(getAngle()).getRadians(); + return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; + }) + .withName("Pivot Go To Angle"); // Fixed the quote here } - - public Command stop() { - return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Pivot"); - } + public Command holdAngle(Rotation2d targetAngle) { + return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold Angle"); + } - + public Command stop() { + return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Pivot"); + } } - From 0b96ca975cb2a4904c971f032ba78341117f49ed Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Sat, 31 Jan 2026 15:53:04 -0500 Subject: [PATCH 05/15] executionlogger --- src/main/java/org/team2342/frc/subsystems/intake/Pivot.java | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 25d371c..c1a7843 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -12,6 +12,7 @@ import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; import org.team2342.frc.Constants.PivotConstants; +import org.team2342.lib.logging.ExecutionLogger; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; @@ -30,6 +31,8 @@ public Pivot(SmartMotorIO pivotMotor) { public void periodic() { pivotMotor.updateInputs(pivotMotorInputs); Logger.processInputs("Intake/Pivot", pivotMotorInputs); + + ExecutionLogger.log("Intake/Pivot"); } @AutoLogOutput(key = "Intake/Pivot/Angle") From c0ac7af246f6cabc7e8b720fe5cafba99e2ccd8c Mon Sep 17 00:00:00 2001 From: aniruddhsridhar Date: Sat, 31 Jan 2026 16:14:13 -0500 Subject: [PATCH 06/15] Alerts added Added disconnected alerts for the pivot motors. --- src/main/java/org/team2342/frc/subsystems/intake/Pivot.java | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index c1a7843..aa53de2 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -7,6 +7,8 @@ package org.team2342.frc.subsystems.intake; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.Alert; +import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.AutoLogOutput; @@ -21,6 +23,8 @@ public class Pivot extends SubsystemBase { private final SmartMotorIO pivotMotor; private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); + private final Alert pivotMotorAlert = new Alert("Pivot motor is disconnected!", AlertType.kError); + public Pivot(SmartMotorIO pivotMotor) { this.pivotMotor = pivotMotor; setName("Pivot"); @@ -31,6 +35,7 @@ public Pivot(SmartMotorIO pivotMotor) { public void periodic() { pivotMotor.updateInputs(pivotMotorInputs); Logger.processInputs("Intake/Pivot", pivotMotorInputs); + Logger.processInputs("Shooter/Hood/Motor", pivotMotorInputs); ExecutionLogger.log("Intake/Pivot"); } From 24f62a67584b7c4635787e2d351f3999683b094f Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Thu, 19 Feb 2026 19:05:49 -0500 Subject: [PATCH 07/15] intake pivot for week 0 --- src/main/java/org/team2342/frc/Constants.java | 1 + .../team2342/frc/subsystems/intake/Pivot.java | 56 +++++++++++-------- 2 files changed, 34 insertions(+), 23 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 50d6ce6..30ab94a 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -127,6 +127,7 @@ public static final class PivotConstants { public static final double CUTOFF_ANGLE = 1.2; public static final double MOVE_ANGLE = 0.5; public static final double AT_TARGET_TOLERANCE = 0.01; + public static final double IN_VOLTAGE = 5.0; public static final SmartMotorConfig PIVOT_CONFIG = new SmartMotorConfig() diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index aa53de2..3c51d80 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -6,29 +6,27 @@ package org.team2342.frc.subsystems.intake; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; import org.team2342.frc.Constants.PivotConstants; import org.team2342.lib.logging.ExecutionLogger; -import org.team2342.lib.motors.smart.SmartMotorIO; -import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; +import org.team2342.lib.motors.dumb.DumbMotorIO; +import org.team2342.lib.motors.dumb.DumbMotorIOInputsAutoLogged; public class Pivot extends SubsystemBase { - private final SmartMotorIO pivotMotor; - private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); + private final DumbMotorIO pivotMotor; + private final DumbMotorIOInputsAutoLogged pivotMotorInputs = new DumbMotorIOInputsAutoLogged(); private final Alert pivotMotorAlert = new Alert("Pivot motor is disconnected!", AlertType.kError); - public Pivot(SmartMotorIO pivotMotor) { + public Pivot(DumbMotorIO pivotMotor) { this.pivotMotor = pivotMotor; setName("Pivot"); - setDefaultCommand(run(() -> pivotMotor.runPosition(PivotConstants.MIN_ANGLE))); + setDefaultCommand(run(() -> pivotMotor.runVoltage(0.0))); } @Override @@ -40,25 +38,37 @@ public void periodic() { ExecutionLogger.log("Intake/Pivot"); } - @AutoLogOutput(key = "Intake/Pivot/Angle") - public Rotation2d getAngle() { - return Rotation2d.fromRadians(pivotMotorInputs.positionRad); - } + // @AutoLogOutput(key = "Intake/Pivot/Angle") + // public Rotation2d getAngle() { + // return Rotation2d.fromRadians(pivotMotorInputs.positionRad); + // } + + // public Command goToAngle(Rotation2d targetAngle) { + // return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) + // .until( + // () -> { + // // Using minus() and getRadians() handles the wrap-around math for you! + // double error = targetAngle.minus(getAngle()).getRadians(); + // return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; + // }) + // .withName("Pivot Go To Angle"); // Fixed the quote here + // } - public Command goToAngle(Rotation2d targetAngle) { - return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) - .until( - () -> { - // Using minus() and getRadians() handles the wrap-around math for you! - double error = targetAngle.minus(getAngle()).getRadians(); - return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; - }) - .withName("Pivot Go To Angle"); // Fixed the quote here + public Command in() { + return run(() -> pivotMotor.runVoltage(PivotConstants.IN_VOLTAGE)) + .withTimeout(2.0) + .withName("Pivot In"); } - public Command holdAngle(Rotation2d targetAngle) { - return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold Angle"); + public Command out() { + return run(() -> pivotMotor.runVoltage(-PivotConstants.IN_VOLTAGE)) + .withTimeout(2.0) + .withName("Pivot Out"); } + // public Command holdAngle(Rotation2d targetAngle) { + // return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold + // Angle"); + // } public Command stop() { return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Pivot"); From c60cf3e5c5319c46784ca1751cad771c4669288d Mon Sep 17 00:00:00 2001 From: abi-appusamy9932 Date: Thu, 19 Feb 2026 19:15:13 -0500 Subject: [PATCH 08/15] pivot setup + out at auto start --- src/main/java/org/team2342/frc/Constants.java | 1 + src/main/java/org/team2342/frc/Robot.java | 4 +++- src/main/java/org/team2342/frc/RobotContainer.java | 10 ++++++++++ 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 30ab94a..79b686e 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -117,6 +117,7 @@ public static final class CANConstants { public static final int[] BR_IDS = {4, 8, 12}; public static final int PDH_ID = 62; + public static final int PIVOT_ID = 18; } public static final class PivotConstants { diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index 56fc0c6..f784b3c 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() { + CommandScheduler.getInstance().schedule(robotContainer.getPivot().out()); + } @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 f4eb702..8c1f713 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -25,6 +25,7 @@ import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.team2342.frc.Constants.CANConstants; import org.team2342.frc.Constants.DriveConstants; +import org.team2342.frc.Constants.PivotConstants; import org.team2342.frc.Constants.VisionConstants; import org.team2342.frc.commands.DriveCommands; import org.team2342.frc.commands.DriveToPose; @@ -35,16 +36,21 @@ import org.team2342.frc.subsystems.drive.ModuleIO; import org.team2342.frc.subsystems.drive.ModuleIOSim; import org.team2342.frc.subsystems.drive.ModuleIOTalonFX; +import org.team2342.frc.subsystems.intake.Pivot; import org.team2342.frc.subsystems.vision.Vision; import org.team2342.frc.subsystems.vision.VisionIO; import org.team2342.frc.subsystems.vision.VisionIOPhoton; import org.team2342.frc.subsystems.vision.VisionIOSim; +import org.team2342.lib.motors.dumb.DumbMotorIO; +import org.team2342.lib.motors.dumb.DumbMotorIOSim; +import org.team2342.lib.motors.dumb.DumbMotorIOTalonFX; import org.team2342.lib.util.AllianceUtils; import org.team2342.lib.util.EnhancedXboxController; public class RobotContainer { @Getter private final Drive drive; @Getter private final Vision vision; + @Getter private final Pivot pivot; private final LoggedDashboardChooser autoChooser; @@ -73,6 +79,8 @@ public RobotContainer() { VisionConstants.LEFT_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); + pivot = + new Pivot(new DumbMotorIOTalonFX(CANConstants.PIVOT_ID, PivotConstants.PIVOT_CONFIG)); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); break; @@ -94,6 +102,7 @@ public RobotContainer() { PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, drive::getRawOdometryPose)); + pivot = new Pivot(new DumbMotorIOSim(null, null)); break; @@ -111,6 +120,7 @@ public RobotContainer() { drive::getTimestampedHeading, new VisionIO() {}, new VisionIO() {}); + pivot = new Pivot(new DumbMotorIO() {}); break; } From 766b3466ab4a769eff4349a030c4800d2aba9f90 Mon Sep 17 00:00:00 2001 From: Phoenix2342-Bot Date: Fri, 20 Feb 2026 00:18:30 +0000 Subject: [PATCH 09/15] Auto-format code --- src/main/java/org/team2342/frc/Constants.java | 5 ----- src/main/java/org/team2342/frc/RobotContainer.java | 9 +++++---- 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index e2f0708..dabec03 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -9,11 +9,6 @@ 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.trajectory.TrapezoidProfile; -import edu.wpi.first.math.util.Units; -import org.team2342.lib.motors.MotorConfig.IdleMode; -import org.team2342.lib.motors.smart.SmartMotorConfig; -import org.team2342.lib.motors.smart.SmartMotorConfig.ControlType; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.trajectory.TrapezoidProfile; diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 82a6175..a4893d4 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -23,9 +23,9 @@ import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.team2342.frc.Constants.CANConstants; import org.team2342.frc.Constants.DriveConstants; -import org.team2342.frc.Constants.PivotConstants; import org.team2342.frc.Constants.IndexerConstants; import org.team2342.frc.Constants.IntakeConstants; +import org.team2342.frc.Constants.PivotConstants; import org.team2342.frc.Constants.ShooterConstants; import org.team2342.frc.Constants.VisionConstants; import org.team2342.frc.commands.DriveCommands; @@ -35,8 +35,8 @@ import org.team2342.frc.subsystems.drive.ModuleIO; import org.team2342.frc.subsystems.drive.ModuleIOSim; import org.team2342.frc.subsystems.drive.ModuleIOTalonFX; -import org.team2342.frc.subsystems.intake.Pivot; import org.team2342.frc.subsystems.indexer.Indexer; +import org.team2342.frc.subsystems.intake.Pivot; import org.team2342.frc.subsystems.intake.Wheels; import org.team2342.frc.subsystems.shooter.Flywheel; import org.team2342.frc.subsystems.shooter.Hood; @@ -47,7 +47,6 @@ import org.team2342.lib.motors.dumb.DumbMotorIO; import org.team2342.lib.motors.dumb.DumbMotorIOSim; import org.team2342.lib.motors.dumb.DumbMotorIOTalonFX; -import org.team2342.lib.util.AllianceUtils; import org.team2342.lib.motors.dumb.DumbMotorIOTalonFXFOC; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOSim; @@ -91,7 +90,9 @@ public RobotContainer() { PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); pivot = - new Pivot(new DumbMotorIOTalonFX(CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); + new Pivot( + new DumbMotorIOTalonFX( + CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); indexer = new Indexer( new DumbMotorIOTalonFXFOC( From a680ac1006f239adf3e043bb53dcd4fc3c7a5fd4 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Mon, 9 Mar 2026 20:15:07 -0400 Subject: [PATCH 10/15] Merging main into intake pivot (again) (#14) Co-authored-by: novA2026 Co-authored-by: abi-appusamy9932 Co-authored-by: Phoenix2342-Bot Co-authored-by: aniruddhsridhar Co-authored-by: CuevasN1 Co-authored-by: abhi-team2342 Co-authored-by: dlaflotte --- .../calibrations/shooter_arducam_800.json | 1 + src/main/java/org/team2342/frc/Constants.java | 146 ++++++++--- src/main/java/org/team2342/frc/Robot.java | 6 + .../java/org/team2342/frc/RobotContainer.java | 243 ++++++++++++++---- .../team2342/frc/subsystems/Conductor.java | 185 +++++++++++++ .../team2342/frc/subsystems/drive/Drive.java | 2 +- .../frc/subsystems/indexer/Indexer.java | 32 +-- .../frc/subsystems/kicker/Kicker.java | 60 +++++ .../frc/subsystems/shooter/Flywheel.java | 50 ++++ .../team2342/frc/subsystems/shooter/Hood.java | 9 + .../frc/subsystems/shooter/Turret.java | 97 +++++++ .../frc/subsystems/vision/Vision.java | 60 ++--- .../org/team2342/frc/util/FiringSolver.java | 115 +++++++++ 13 files changed, 879 insertions(+), 127 deletions(-) create mode 100644 src/main/deploy/calibrations/shooter_arducam_800.json create mode 100644 src/main/java/org/team2342/frc/subsystems/Conductor.java create mode 100644 src/main/java/org/team2342/frc/subsystems/kicker/Kicker.java create mode 100644 src/main/java/org/team2342/frc/subsystems/shooter/Turret.java create mode 100644 src/main/java/org/team2342/frc/util/FiringSolver.java diff --git a/src/main/deploy/calibrations/shooter_arducam_800.json b/src/main/deploy/calibrations/shooter_arducam_800.json new file mode 100644 index 0000000..91e1c5e --- /dev/null +++ b/src/main/deploy/calibrations/shooter_arducam_800.json @@ -0,0 +1 @@ +{"resolution":{"width":800.0,"height":600.0},"cameraIntrinsics":{"rows":3,"cols":3,"type":6,"data":[681.9492187553824,0.0,393.323658696967,0.0,682.4003705196471,316.2701656805164,0.0,0.0,1.0]},"distCoeffs":{"rows":1,"cols":8,"type":6,"data":[0.047346658462759796,-0.0833406104288882,3.3568756453426616E-4,6.959616512593998E-5,0.032803729056886825,-0.0017050420065646394,0.0034216038589405732,-0.0013062921211588517]},"calobjectWarp":[-3.017935796189912E-4,7.145756248236368E-5],"observations":[{"locationInObjectSpace":[{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":378.3189392089844,"y":152.21136474609375},{"x":406.81903076171875,"y":150.5050811767578},{"x":435.3324279785156,"y":148.7574462890625},{"x":464.4139709472656,"y":147.00831604003906},{"x":494.0133056640625,"y":145.17727661132812},{"x":523.7711791992188,"y":143.35816955566406},{"x":553.6189575195312,"y":141.6733856201172},{"x":583.9456787109375,"y":139.5655517578125},{"x":614.4834594726562,"y":137.97552490234375},{"x":645.1041259765625,"y":135.9368133544922},{"x":676.7672119140625,"y":134.06137084960938},{"x":708.0502319335938,"y":132.10464477539062},{"x":349.15576171875,"y":179.5871124267578},{"x":378.1731262207031,"y":177.90472412109375},{"x":407.0248718261719,"y":176.29373168945312},{"x":435.972900390625,"y":174.6495819091797},{"x":465.4890441894531,"y":173.05078125},{"x":494.9942932128906,"y":171.32501220703125},{"x":525.2404174804688,"y":169.79684448242188},{"x":555.59130859375,"y":167.9044189453125},{"x":586.443115234375,"y":166.18174743652344},{"x":617.2210083007812,"y":164.3078155517578},{"x":648.76123046875,"y":162.85438537597656},{"x":680.64208984375,"y":160.92820739746094},{"x":712.4284057617188,"y":159.165283203125},{"x":319.97247314453125,"y":207.24717712402344},{"x":407.0084533691406,"y":202.66712951660156},{"x":436.4399108886719,"y":201.021240234375},{"x":466.42877197265625,"y":199.6578826904297},{"x":496.36041259765625,"y":198.00579833984375},{"x":526.8967895507812,"y":196.40487670898438},{"x":557.732421875,"y":194.86676025390625},{"x":588.9366455078125,"y":193.250732421875},{"x":620.3611450195312,"y":191.567138671875},{"x":652.0652465820312,"y":189.91258239746094},{"x":684.2532348632812,"y":188.1542205810547},{"x":716.5776977539062,"y":186.5725860595703},{"x":318.99053955078125,"y":234.0193328857422},{"x":407.0911865234375,"y":229.92330932617188},{"x":437.0247497558594,"y":228.19699096679688},{"x":467.2634582519531,"y":226.9062957763672},{"x":497.6654357910156,"y":225.30567932128906},{"x":528.655029296875,"y":224.01242065429688},{"x":559.77734375,"y":222.39804077148438},{"x":591.5267944335938,"y":220.956298828125},{"x":623.19287109375,"y":219.43484497070312},{"x":655.5066528320312,"y":218.04307556152344},{"x":688.30029296875,"y":216.2910919189453},{"x":721.2858276367188,"y":214.75302124023438},{"x":317.97161865234375,"y":261.0192565917969},{"x":347.2662658691406,"y":260.1695251464844},{"x":377.21197509765625,"y":258.71661376953125},{"x":407.23150634765625,"y":257.4964599609375},{"x":437.64349365234375,"y":256.1988525390625},{"x":468.1019287109375,"y":254.86866760253906},{"x":499.02691650390625,"y":253.6736602783203},{"x":530.4417114257812,"y":252.1702117919922},{"x":561.9138793945312,"y":250.99330139160156},{"x":593.93701171875,"y":249.38458251953125},{"x":626.5515747070312,"y":248.08279418945312},{"x":659.2053833007812,"y":246.655517578125},{"x":692.454833984375,"y":245.20240783691406},{"x":725.7931518554688,"y":243.88339233398438},{"x":317.0743103027344,"y":289.3258056640625},{"x":346.8901062011719,"y":288.1692199707031},{"x":376.9767150878906,"y":287.0377502441406},{"x":407.4256591796875,"y":285.95745849609375},{"x":438.0179138183594,"y":284.6495361328125},{"x":469.1166687011719,"y":283.5600280761719},{"x":498.36151123046875,"y":281.02081298828125},{"x":532.3516845703125,"y":281.17120361328125},{"x":564.2351684570312,"y":279.8980407714844},{"x":596.8384399414062,"y":278.8991394042969},{"x":629.7559814453125,"y":277.5153503417969},{"x":662.94287109375,"y":276.18487548828125},{"x":696.6587524414062,"y":275.0389099121094},{"x":730.4359130859375,"y":273.7704162597656},{"x":315.87127685546875,"y":318.5631103515625},{"x":346.14031982421875,"y":317.260498046875},{"x":376.7519226074219,"y":316.2558898925781},{"x":407.5174865722656,"y":315.3186950683594},{"x":438.7944641113281,"y":314.0711364746094},{"x":470.18475341796875,"y":313.0690002441406},{"x":501.98486328125,"y":312.1424255371094},{"x":534.35888671875,"y":310.9291076660156},{"x":566.7740478515625,"y":310.0253601074219},{"x":599.8558959960938,"y":308.9830017089844},{"x":633.1785278320312,"y":307.8343811035156},{"x":666.9324951171875,"y":306.89013671875},{"x":700.9960327148438,"y":305.832763671875},{"x":735.2266845703125,"y":304.4384765625},{"x":314.8581848144531,"y":347.9692687988281},{"x":345.4751892089844,"y":346.9300537109375},{"x":376.457275390625,"y":346.1026916503906},{"x":407.8572998046875,"y":345.1694030761719},{"x":439.3410339355469,"y":344.20758056640625},{"x":471.31005859375,"y":343.3361511230469},{"x":503.34503173828125,"y":342.4425964355469},{"x":536.3975219726562,"y":341.4584045410156},{"x":569.1263427734375,"y":340.60400390625},{"x":602.7446899414062,"y":339.8112487792969},{"x":636.8300170898438,"y":339.0753173828125},{"x":670.9169921875,"y":337.9704284667969},{"x":705.2396850585938,"y":337.0020446777344},{"x":740.43896484375,"y":336.2787780761719},{"x":313.58056640625,"y":378.6322937011719},{"x":344.9569091796875,"y":377.8987121582031},{"x":376.13751220703125,"y":377.0419921875},{"x":407.94244384765625,"y":376.13787841796875},{"x":440.0059509277344,"y":375.59332275390625},{"x":472.50384521484375,"y":374.71759033203125},{"x":505.1213073730469,"y":374.0430908203125},{"x":538.4515991210938,"y":373.2359924316406},{"x":571.8696899414062,"y":372.4520263671875},{"x":605.874755859375,"y":371.7989196777344},{"x":640.29736328125,"y":371.0213623046875},{"x":675.0682373046875,"y":370.3419494628906},{"x":710.3533325195312,"y":369.4290466308594},{"x":745.5046997070312,"y":368.7735900878906},{"x":312.33892822265625,"y":410.0322265625},{"x":343.9811096191406,"y":409.3191833496094},{"x":375.88629150390625,"y":408.65283203125},{"x":408.16845703125,"y":408.13818359375},{"x":440.4402770996094,"y":407.3761901855469},{"x":473.6576232910156,"y":406.85406494140625},{"x":506.8109436035156,"y":406.1507568359375},{"x":540.5580444335938,"y":405.8326110839844},{"x":574.418701171875,"y":405.0469665527344},{"x":609.1710815429688,"y":404.6157531738281},{"x":644.0364990234375,"y":404.06207275390625},{"x":679.3883056640625,"y":403.7637939453125},{"x":714.9984741210938,"y":402.9879150390625},{"x":751.001220703125,"y":402.5251770019531}],"reprojectionErrors":[{"x":0.353485107421875,"y":-0.0764312744140625},{"x":0.368133544921875,"y":-0.1362152099609375},{"x":0.152313232421875,"y":-0.1190032958984375},{"x":0.06658935546875,"y":-0.1185150146484375},{"x":0.180908203125,"y":-0.2570343017578125},{"x":0.10748291015625,"y":0.0229339599609375},{"x":0.11529541015625,"y":-0.2193603515625},{"x":0.33380126953125,"y":-0.017303466796875},{"x":-0.19537353515625,"y":0.0172882080078125},{"x":-0.04876708984375,"y":0.12908935546875},{"x":0.311614990234375,"y":-0.0500030517578125},{"x":-0.100982666015625,"y":-0.0568084716796875},{"x":0.18194580078125,"y":-0.1951904296875},{"x":0.146697998046875,"y":-0.3005523681640625},{"x":0.41729736328125,"y":-0.2837371826171875},{"x":0.24334716796875,"y":-0.4692230224609375},{"x":0.26239013671875,"y":-0.2950439453125},{"x":0.07952880859375,"y":-0.2950897216796875},{"x":0.27093505859375,"y":-0.1482391357421875},{"x":0.00164794921875,"y":-0.4261627197265625},{"x":-0.30548095703125,"y":-0.2354736328125},{"x":-0.2139892578125,"y":-0.212066650390625},{"x":0.155242919921875,"y":-0.0170745849609375},{"x":0.05206298828125,"y":-0.1731719970703125},{"x":0.195648193359375,"y":-0.115753173828125},{"x":0.083160400390625,"y":-0.345611572265625},{"x":0.23187255859375,"y":-0.361602783203125},{"x":0.1243896484375,"y":-0.3567962646484375},{"x":0.10528564453125,"y":-0.288665771484375},{"x":0.11663818359375,"y":-0.2537078857421875},{"x":-0.04461669921875,"y":-0.1190032958984375},{"x":-0.0296630859375,"y":-0.1649322509765625},{"x":0.083770751953125,"y":-0.0998382568359375},{"x":0.063751220703125,"y":-0.3892669677734375},{"x":0.103790283203125,"y":-0.13409423828125},{"x":0.148193359375,"y":-0.319061279296875},{"x":0.3404541015625,"y":-0.1985626220703125},{"x":0.2578125,"y":-0.3897705078125},{"x":0.3328857421875,"y":-0.2908782958984375},{"x":0.1923828125,"y":-0.4001007080078125},{"x":-0.10772705078125,"y":-0.1529998779296875},{"x":-0.27813720703125,"y":-0.1236114501953125},{"x":0.018585205078125,"y":0.298614501953125},{"x":0.16424560546875,"y":-0.18524169921875},{"x":-0.028564453125,"y":-0.070404052734375},{"x":0.01922607421875,"y":-0.1927490234375},{"x":-0.00921630859375,"y":-0.241973876953125},{"x":0.233917236328125,"y":-0.2628936767578125},{"x":0.330230712890625,"y":-0.423187255859375},{"x":0.2581787109375,"y":-0.279144287109375},{"x":0.451904296875,"y":-0.4656829833984375},{"x":0.41949462890625,"y":-0.224365234375},{"x":0.1220703125,"y":-0.2938385009765625},{"x":0.11334228515625,"y":-0.241607666015625},{"x":-0.1614990234375,"y":-0.167236328125},{"x":-0.1942138671875,"y":-0.230560302734375},{"x":-0.2001953125,"y":0.129547119140625},{"x":-0.17974853515625,"y":0.083282470703125},{"x":-0.109039306640625,"y":0.007781982421875},{"x":-0.077606201171875,"y":-0.12298583984375},{"x":0.135498046875,"y":-0.0301513671875},{"x":0.1689453125,"y":-0.159698486328125},{"x":2.38507080078125,"y":1.156585693359375},{"x":0.18646240234375,"y":-0.22052001953125},{"x":0.4268798828125,"y":-0.1778564453125},{"x":0.28167724609375,"y":-0.413116455078125},{"x":0.15802001953125,"y":-0.267059326171875},{"x":0.1026611328125,"y":-0.177825927734375},{"x":-0.14251708984375,"y":-0.27655029296875},{"x":-0.1466064453125,"y":-0.19921875},{"x":-0.1722412109375,"y":0.039031982421875},{"x":-0.21044921875,"y":-0.02447509765625},{"x":-0.070587158203125,"y":-0.1590576171875},{"x":-0.108001708984375,"y":0.013092041015625},{"x":0.077362060546875,"y":-0.063751220703125},{"x":0.191070556640625,"y":-0.21966552734375},{"x":0.0709228515625,"y":-0.09228515625},{"x":0.251708984375,"y":-0.277862548828125},{"x":0.10968017578125,"y":-0.328125},{"x":0.0726318359375,"y":-0.275421142578125},{"x":-0.04815673828125,"y":-0.43023681640625},{"x":-0.12908935546875,"y":-0.475067138671875},{"x":-0.02606201171875,"y":-0.18597412109375},{"x":-0.317779541015625,"y":0.107879638671875},{"x":-0.272430419921875,"y":0.2294921875},{"x":-0.2529296875,"y":0.135955810546875},{"x":-0.3099365234375,"y":0.145172119140625},{"x":-0.106964111328125,"y":0.179718017578125},{"x":-0.04351806640625,"y":0.12078857421875},{"x":0.30194091796875,"y":0.080902099609375},{"x":-0.0201416015625,"y":0.128662109375},{"x":0.3336181640625,"y":0.04364013671875},{"x":0.15191650390625,"y":-0.10589599609375},{"x":-0.14056396484375,"y":-0.315093994140625},{"x":-0.07666015625,"y":-0.158111572265625},{"x":0.111572265625,"y":-0.140350341796875},{"x":-0.21484375,"y":-0.370391845703125},{"x":-0.260772705078125,"y":-0.0013427734375},{"x":-0.5435791015625,"y":-0.02984619140625},{"x":-0.281707763671875,"y":0.062103271484375},{"x":-0.29290771484375,"y":0.19879150390625},{"x":-0.20904541015625,"y":-0.026702880859375},{"x":-0.203704833984375,"y":0.076416015625},{"x":0.040283203125,"y":-0.024261474609375},{"x":-0.068115234375,"y":0.00518798828125},{"x":0.0982666015625,"y":0.009063720703125},{"x":0.04254150390625,"y":-0.120330810546875},{"x":-0.063720703125,"y":-0.12762451171875},{"x":-0.149169921875,"y":-0.235321044921875},{"x":-0.377685546875,"y":-0.11181640625},{"x":-0.09930419921875,"y":-0.247894287109375},{"x":-0.27777099609375,"y":0.0308837890625},{"x":-0.382354736328125,"y":0.1468505859375},{"x":-0.39093017578125,"y":0.21405029296875},{"x":-0.41497802734375,"y":0.12750244140625},{"x":-0.06463623046875,"y":0.286346435546875},{"x":-0.2933349609375,"y":0.203369140625},{"x":-0.089111328125,"y":0.299652099609375},{"x":-0.10736083984375,"y":0.008880615234375},{"x":0.13458251953125,"y":0.18377685546875},{"x":-0.13922119140625,"y":0.00244140625},{"x":-0.147705078125,"y":-0.058197021484375},{"x":-0.261962890625,"y":-0.375946044921875},{"x":-0.25177001953125,"y":-0.217803955078125},{"x":-0.2491455078125,"y":-0.3743896484375}],"optimisedCameraToObject":{"translation":{"x":-0.03763434206874378,"y":-0.0847575279698703,"z":0.3605792182242429},"rotation":{"quaternion":{"W":0.9862203034791447,"X":-0.15448699856128928,"Y":0.058695642430209,"Z":-0.00762245634510681}}},"cornersUsed":[false,false,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,true,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,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],"snapshotName":"img0.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img0.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":76.899169921875,"y":187.75946044921875},{"x":105.18309783935547,"y":187.2933807373047},{"x":133.85391235351562,"y":187.13711547851562},{"x":162.59739685058594,"y":186.4613800048828},{"x":191.13836669921875,"y":186.0867919921875},{"x":220.0327911376953,"y":185.74813842773438},{"x":248.73570251464844,"y":185.5013427734375},{"x":277.3772888183594,"y":184.7583770751953},{"x":306.1716003417969,"y":184.7948455810547},{"x":334.6666259765625,"y":184.29100036621094},{"x":363.3582458496094,"y":184.0808563232422},{"x":391.80615234375,"y":183.72950744628906},{"x":420.6057434082031,"y":183.18695068359375},{"x":449.088623046875,"y":182.73294067382812},{"x":75.64109802246094,"y":215.89657592773438},{"x":104.30198669433594,"y":215.69871520996094},{"x":133.12298583984375,"y":215.04290771484375},{"x":162.01882934570312,"y":214.77442932128906},{"x":190.66331481933594,"y":214.3427276611328},{"x":219.500244140625,"y":214.08245849609375},{"x":305.8384704589844,"y":212.68626403808594},{"x":334.8121643066406,"y":212.37644958496094},{"x":363.7453918457031,"y":212.01116943359375},{"x":392.1724548339844,"y":211.84140014648438},{"x":421.2458801269531,"y":211.61614990234375},{"x":449.78857421875,"y":210.9053497314453},{"x":74.62879943847656,"y":244.02308654785156},{"x":103.44353485107422,"y":243.6868133544922},{"x":132.16529846191406,"y":243.29708862304688},{"x":161.2514190673828,"y":242.83628845214844},{"x":190.19729614257812,"y":242.524658203125},{"x":219.1487579345703,"y":242.02896118164062},{"x":305.9972839355469,"y":241.02833557128906},{"x":334.8914794921875,"y":240.5767822265625},{"x":363.8080139160156,"y":240.28282165527344},{"x":392.5718994140625,"y":240.13755798339844},{"x":421.56378173828125,"y":239.5685577392578},{"x":450.1075744628906,"y":239.05706787109375},{"x":73.41504669189453,"y":272.72393798828125},{"x":102.36351776123047,"y":272.2706604003906},{"x":131.45506286621094,"y":271.8775634765625},{"x":160.32810974121094,"y":271.423828125},{"x":247.74261474609375,"y":270.3057556152344},{"x":276.8076477050781,"y":270.1116638183594},{"x":305.8274841308594,"y":269.5170593261719},{"x":334.9936828613281,"y":269.2425537109375},{"x":364.0023498535156,"y":268.7849426269531},{"x":392.8902893066406,"y":268.48016357421875},{"x":422.08917236328125,"y":267.9945373535156},{"x":450.7052001953125,"y":267.9103698730469},{"x":71.94725799560547,"y":301.4524841308594},{"x":101.2667465209961,"y":301.08056640625},{"x":130.63499450683594,"y":300.4371643066406},{"x":159.6015625,"y":300.0776062011719},{"x":247.31297302246094,"y":299.052490234375},{"x":276.74334716796875,"y":298.676025390625},{"x":305.8343505859375,"y":298.23687744140625},{"x":335.20538330078125,"y":298.08447265625},{"x":364.2394714355469,"y":297.6114501953125},{"x":393.2843017578125,"y":297.1811218261719},{"x":422.4312438964844,"y":297.0137634277344},{"x":451.7033996582031,"y":296.44171142578125},{"x":71.00234985351562,"y":330.638916015625},{"x":100.17164611816406,"y":329.91448974609375},{"x":129.3188934326172,"y":329.51214599609375},{"x":158.93341064453125,"y":329.2183837890625},{"x":188.1029510498047,"y":328.816650390625},{"x":217.7075653076172,"y":328.3854064941406},{"x":247.1174774169922,"y":328.02203369140625},{"x":276.3537902832031,"y":327.8335876464844},{"x":305.7620849609375,"y":327.425537109375},{"x":335.0992126464844,"y":326.98858642578125},{"x":364.30816650390625,"y":326.3985290527344},{"x":393.7198791503906,"y":326.1217041015625},{"x":423.0872497558594,"y":325.8231506347656},{"x":452.1015319824219,"y":325.4599609375},{"x":69.56275939941406,"y":359.9228515625},{"x":98.88095092773438,"y":359.37127685546875},{"x":128.4189910888672,"y":359.1329650878906},{"x":157.90939331054688,"y":358.6623840332031},{"x":187.35951232910156,"y":358.3089904785156},{"x":217.16015625,"y":357.8843078613281},{"x":246.64942932128906,"y":357.61553955078125},{"x":276.1449890136719,"y":357.0327453613281},{"x":305.794189453125,"y":356.7278137207031},{"x":335.0511474609375,"y":356.0926208496094},{"x":364.42266845703125,"y":356.0133056640625},{"x":393.8730163574219,"y":355.32196044921875},{"x":423.62701416015625,"y":355.05059814453125},{"x":452.75567626953125,"y":354.7718811035156},{"x":68.2682876586914,"y":389.4649353027344},{"x":97.77266693115234,"y":389.1088562011719},{"x":127.32037353515625,"y":388.91387939453125},{"x":157.11058044433594,"y":388.2947082519531},{"x":186.7942657470703,"y":387.92083740234375},{"x":216.6844482421875,"y":387.2876892089844},{"x":246.06349182128906,"y":387.02001953125},{"x":275.8543701171875,"y":386.7534484863281},{"x":305.4535827636719,"y":386.15631103515625},{"x":335.10693359375,"y":386.0321960449219},{"x":364.8882141113281,"y":385.5914306640625},{"x":394.35565185546875,"y":384.9740905761719},{"x":423.98779296875,"y":384.8282470703125},{"x":453.41302490234375,"y":384.5780029296875},{"x":66.69884490966797,"y":419.8585510253906},{"x":96.45311737060547,"y":419.2421569824219},{"x":126.470947265625,"y":418.7684631347656},{"x":156.14212036132812,"y":418.2942199707031},{"x":185.92779541015625,"y":418.029541015625},{"x":215.83653259277344,"y":417.46337890625},{"x":245.5550994873047,"y":417.227294921875},{"x":275.5851135253906,"y":416.67474365234375},{"x":305.31207275390625,"y":416.23492431640625},{"x":335.4060363769531,"y":415.9866027832031},{"x":364.9503173828125,"y":415.7610778808594},{"x":394.7968444824219,"y":415.1280822753906},{"x":424.77685546875,"y":414.5982360839844},{"x":454.318115234375,"y":414.5118713378906},{"x":65.26226806640625,"y":450.033447265625},{"x":95.22583770751953,"y":449.6563415527344},{"x":125.14537811279297,"y":449.17218017578125},{"x":155.0216827392578,"y":448.896728515625},{"x":185.0144805908203,"y":448.1705322265625},{"x":215.49667358398438,"y":447.73736572265625},{"x":245.09164428710938,"y":447.38397216796875},{"x":275.3024597167969,"y":446.98699951171875},{"x":305.3636474609375,"y":446.56756591796875},{"x":335.12847900390625,"y":446.2196044921875},{"x":365.0210876464844,"y":445.7785339355469},{"x":394.8717346191406,"y":445.67431640625},{"x":425.0079650878906,"y":445.0953674316406},{"x":454.8571472167969,"y":444.7685241699219}],"reprojectionErrors":[{"x":-0.0359039306640625,"y":0.036590576171875},{"x":0.26172637939453125,"y":0.09234619140625},{"x":0.1914215087890625,"y":-0.154632568359375},{"x":0.0644683837890625,"y":0.1249847412109375},{"x":0.153106689453125,"y":0.110626220703125},{"x":-0.1015472412109375,"y":0.067535400390625},{"x":-0.157470703125,"y":-0.060150146484375},{"x":-0.147796630859375,"y":0.31561279296875},{"x":-0.289520263671875,"y":-0.080718994140625},{"x":-0.133575439453125,"y":0.0706024169921875},{"x":-0.17877197265625,"y":-0.064361572265625},{"x":0.012237548828125,"y":-0.0507049560546875},{"x":-0.158843994140625,"y":0.16162109375},{"x":-0.026580810546875,"y":0.2928924560546875},{"x":0.026824951171875,"y":-0.1427764892578125},{"x":0.08887481689453125,"y":-0.352325439453125},{"x":0.00994873046875,"y":-0.0977630615234375},{"x":-0.127655029296875,"y":-0.2243499755859375},{"x":-7.01904296875E-4,"y":-0.18145751953125},{"x":-0.055938720703125,"y":-0.3037109375},{"x":-0.343017578125,"y":-0.0494384765625},{"x":0.01068115234375,"y":-0.22369384765625},{"x":-0.29254150390625,"y":-0.3359375},{"x":-0.078521728515625,"y":0.0439453125},{"x":-0.17324066162109375,"y":-0.0356597900390625},{"x":-0.1217803955078125,"y":-0.1038055419921875},{"x":0.041961669921875,"y":-0.1132965087890625},{"x":-0.1423492431640625,"y":-0.04644775390625},{"x":-0.1730804443359375,"y":-0.12347412109375},{"x":-0.199066162109375,"y":-0.0111083984375},{"x":-0.239166259765625,"y":-0.1280059814453125},{"x":-0.196563720703125,"y":-0.03802490234375},{"x":-0.0985107421875,"y":-0.0811920166015625},{"x":0.257843017578125,"y":0.0910491943359375},{"x":-0.18918609619140625,"y":-0.22149658203125},{"x":-0.12630462646484375,"y":-0.169586181640625},{"x":-0.18701171875,"y":-0.173583984375},{"x":-0.0127410888671875,"y":-0.1126708984375},{"x":-0.2167510986328125,"y":-0.14691162109375},{"x":-0.1988525390625,"y":-0.32806396484375},{"x":-0.134429931640625,"y":-0.104217529296875},{"x":-0.218048095703125,"y":-0.1959228515625},{"x":-0.106353759765625,"y":-0.019012451171875},{"x":0.3231201171875,"y":-0.282562255859375},{"x":0.03125,"y":-0.147979736328125},{"x":-0.129791259765625,"y":-0.174285888671875},{"x":-0.319915771484375,"y":0.07415771484375},{"x":-0.09173583984375,"y":0.04205322265625},{"x":-0.14971923828125,"y":-0.0875244140625},{"x":-0.34942626953125,"y":-0.08905029296875},{"x":-0.208404541015625,"y":-0.0244140625},{"x":-0.34918212890625,"y":-0.242950439453125},{"x":-0.15777587890625,"y":-0.137298583984375},{"x":0.015045166015625,"y":-0.070709228515625},{"x":-0.2891845703125,"y":-0.239471435546875},{"x":-0.1509552001953125,"y":0.089935302734375},{"x":0.0291748046875,"y":0.099517822265625},{"x":-0.241180419921875,"y":0.002838134765625},{"x":-0.0528564453125,"y":0.0164794921875},{"x":-0.2890167236328125,"y":0.06201171875},{"x":-0.32293701171875,"y":0.042083740234375},{"x":-0.1788330078125,"y":-0.1502685546875},{"x":-0.20538330078125,"y":-0.12054443359375},{"x":-0.16253662109375,"y":-0.059356689453125},{"x":0.003631591796875,"y":0.15753173828125},{"x":-0.040924072265625,"y":0.063812255859375},{"x":-0.0521240234375,"y":-0.005523681640625},{"x":0.275634765625,"y":-0.00750732421875},{"x":-0.1332550048828125,"y":-0.12969970703125},{"x":0.0071563720703125,"y":0.0301513671875},{"x":-0.0522308349609375,"y":-0.12200927734375},{"x":-0.0470428466796875,"y":-0.040618896484375},{"x":0.01226806640625,"y":-0.075103759765625},{"x":-0.26824951171875,"y":-0.036956787109375},{"x":-0.2298126220703125,"y":-0.153289794921875},{"x":-0.193206787109375,"y":0.04583740234375},{"x":-0.30889892578125,"y":-0.03143310546875},{"x":-0.034149169921875,"y":0.223114013671875},{"x":0.121124267578125,"y":-0.07666015625},{"x":0.18951416015625,"y":0.2371826171875},{"x":-0.056915283203125,"y":0.1326904296875},{"x":0.3077392578125,"y":0.037261962890625},{"x":-0.1411285400390625,"y":0.026824951171875},{"x":-0.0337677001953125,"y":-0.00543212890625},{"x":0.05051422119140625,"y":-0.198577880859375},{"x":-0.090606689453125,"y":0.032684326171875},{"x":-0.111236572265625,"y":0.018890380859375},{"x":-0.32757568359375,"y":0.264739990234375},{"x":-0.025115966796875,"y":0.14544677734375},{"x":-0.1300048828125,"y":0.02545166015625},{"x":-0.041900634765625,"y":0.2364501953125},{"x":-0.009735107421875,"y":-0.02508544921875},{"x":-0.110504150390625,"y":0.030548095703125},{"x":0.09442138671875,"y":0.263336181640625},{"x":0.12335205078125,"y":0.02520751953125},{"x":0.34478759765625,"y":-0.10784912109375},{"x":0.10693359375,"y":-0.35699462890625},{"x":0.11962890625,"y":-0.12548828125},{"x":-0.11078643798828125,"y":-0.03753662109375},{"x":0.022735595703125,"y":0.050140380859375},{"x":0.0558319091796875,"y":-0.07257080078125},{"x":-0.023223876953125,"y":0.10546875},{"x":0.0955963134765625,"y":-0.047271728515625},{"x":-0.092498779296875,"y":0.115753173828125},{"x":0.0238037109375,"y":0.165435791015625},{"x":-0.228790283203125,"y":0.023040771484375},{"x":0.063262939453125,"y":-0.1427001953125},{"x":0.04486083984375,"y":0.0985107421875},{"x":-0.11846923828125,"y":0.23614501953125},{"x":0.142333984375,"y":-0.070159912109375},{"x":0.202728271484375,"y":-0.20452880859375},{"x":0.16349029541015625,"y":-0.208740234375},{"x":0.18892669677734375,"y":-0.10784912109375},{"x":0.2750396728515625,"y":-0.217620849609375},{"x":0.2588958740234375,"y":0.121490478515625},{"x":-0.23565673828125,"y":0.16571044921875},{"x":0.1648101806640625,"y":0.12835693359375},{"x":-0.0460205078125,"y":0.132843017578125},{"x":-0.10589599609375,"y":0.158050537109375},{"x":0.12872314453125,"y":0.110107421875},{"x":0.23040771484375,"y":0.153656005859375},{"x":0.365753173828125,"y":-0.1412353515625},{"x":0.20391845703125,"y":0.03704833984375},{"x":0.31439208984375,"y":-0.03826904296875}],"optimisedCameraToObject":{"translation":{"x":-0.16590055820430313,"y":-0.06730648398088766,"z":0.3575036869517637},"rotation":{"quaternion":{"W":0.9981983185733091,"X":-0.059651100177469926,"Y":-1.6586363524731285E-4,"Z":-0.006468039447187371}}},"cornersUsed":[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,true,true,true,true,true,true,true,true,true,false,false,true,true,true,true,true,true,true,true,true,true,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],"snapshotName":"img1.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img1.png"},{"locationInObjectSpace":[{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":119.23145294189453,"y":23.006193161010742},{"x":145.09075927734375,"y":23.45477294921875},{"x":223.75341796875,"y":24.8029842376709},{"x":249.8388214111328,"y":25.10687828063965},{"x":275.8392333984375,"y":25.435646057128906},{"x":301.9832458496094,"y":26.162569046020508},{"x":327.9410400390625,"y":26.683340072631836},{"x":354.29522705078125,"y":27.258041381835938},{"x":380.1432189941406,"y":27.69608497619629},{"x":406.72125244140625,"y":28.09194564819336},{"x":64.93456268310547,"y":46.024356842041016},{"x":90.92504119873047,"y":46.463218688964844},{"x":116.60436248779297,"y":46.31937026977539},{"x":142.5234832763672,"y":46.6827507019043},{"x":221.3769989013672,"y":48.36956787109375},{"x":248.03958129882812,"y":48.72877502441406},{"x":274.21044921875,"y":49.343284606933594},{"x":300.65167236328125,"y":50.00016784667969},{"x":327.1275329589844,"y":50.23723602294922},{"x":353.2151184082031,"y":51.01109313964844},{"x":379.6609191894531,"y":51.094181060791016},{"x":406.0353088378906,"y":51.75210189819336},{"x":61.37628173828125,"y":70.01480865478516},{"x":87.65737915039062,"y":69.91157531738281},{"x":113.8106460571289,"y":70.72314453125},{"x":140.19869995117188,"y":70.57369995117188},{"x":219.8733673095703,"y":72.27037811279297},{"x":246.1040496826172,"y":72.64754486083984},{"x":272.5821838378906,"y":73.19933319091797},{"x":299.2142639160156,"y":73.71522521972656},{"x":325.9399108886719,"y":74.19755554199219},{"x":352.20269775390625,"y":74.78555297851562},{"x":378.97564697265625,"y":75.24357604980469},{"x":405.5675048828125,"y":75.86514282226562},{"x":57.98149871826172,"y":94.0026626586914},{"x":84.0950927734375,"y":94.22865295410156},{"x":110.85147094726562,"y":94.68023681640625},{"x":137.64334106445312,"y":94.91490936279297},{"x":164.1807861328125,"y":95.81697082519531},{"x":190.8153839111328,"y":96.1910400390625},{"x":217.83091735839844,"y":96.46973419189453},{"x":244.65972900390625,"y":97.25603485107422},{"x":271.1261291503906,"y":97.28865814208984},{"x":297.81817626953125,"y":97.87767028808594},{"x":324.9164733886719,"y":98.69058227539062},{"x":351.31378173828125,"y":99.24746704101562},{"x":378.11199951171875,"y":99.53378295898438},{"x":404.65106201171875,"y":100.38396453857422},{"x":54.64311981201172,"y":118.34431457519531},{"x":81.27322387695312,"y":118.36468505859375},{"x":108.09088134765625,"y":119.0025405883789},{"x":134.84437561035156,"y":119.82585144042969},{"x":161.62185668945312,"y":120.3440170288086},{"x":188.92550659179688,"y":120.58607482910156},{"x":215.81961059570312,"y":121.04488372802734},{"x":242.85415649414062,"y":121.79277038574219},{"x":269.3731689453125,"y":122.04295349121094},{"x":296.5672607421875,"y":122.70764923095703},{"x":323.64251708984375,"y":123.32736206054688},{"x":350.571044921875,"y":123.8531723022461},{"x":377.2510070800781,"y":124.34019470214844},{"x":404.3385009765625,"y":124.90424346923828},{"x":51.13479995727539,"y":143.41781616210938},{"x":78.02568054199219,"y":143.79473876953125},{"x":105.08840942382812,"y":144.13905334472656},{"x":132.116455078125,"y":144.83651733398438},{"x":159.00787353515625,"y":145.24215698242188},{"x":186.51632690429688,"y":145.68783569335938},{"x":213.71409606933594,"y":145.84657287597656},{"x":240.9678192138672,"y":146.7018280029297},{"x":267.89349365234375,"y":147.1817626953125},{"x":295.1270446777344,"y":147.99790954589844},{"x":322.2030029296875,"y":148.3695068359375},{"x":349.40179443359375,"y":149.0837860107422},{"x":376.5249938964844,"y":149.2692413330078},{"x":403.81695556640625,"y":149.9873504638672},{"x":47.777503967285156,"y":168.6764678955078},{"x":74.8073959350586,"y":169.0817413330078},{"x":101.98265838623047,"y":169.661865234375},{"x":129.1924591064453,"y":170.0243682861328},{"x":156.46087646484375,"y":170.76513671875},{"x":184.0392608642578,"y":170.84310913085938},{"x":211.68202209472656,"y":171.71499633789062},{"x":238.96548461914062,"y":171.9718780517578},{"x":266.5332336425781,"y":172.84803771972656},{"x":293.7021789550781,"y":173.27174377441406},{"x":321.13519287109375,"y":173.9038848876953},{"x":348.64105224609375,"y":174.3502960205078},{"x":375.8575439453125,"y":175.1556396484375},{"x":403.1531982421875,"y":175.41368103027344},{"x":44.18832015991211,"y":194.14620971679688},{"x":71.4551010131836,"y":194.6529541015625},{"x":98.92626190185547,"y":194.9884033203125},{"x":126.72201538085938,"y":195.8857879638672},{"x":154.05686950683594,"y":196.10328674316406},{"x":181.76727294921875,"y":196.8448028564453},{"x":209.45947265625,"y":197.31982421875},{"x":237.0241241455078,"y":197.9214324951172},{"x":264.65606689453125,"y":198.36294555664062},{"x":292.18975830078125,"y":199.1100311279297},{"x":320.00872802734375,"y":199.8404541015625},{"x":347.4636535644531,"y":200.18145751953125},{"x":375.07122802734375,"y":200.80931091308594},{"x":402.87994384765625,"y":201.31802368164062},{"x":40.692352294921875,"y":220.3870086669922},{"x":68.18083190917969,"y":220.94583129882812},{"x":95.96199798583984,"y":221.3776397705078},{"x":123.80506134033203,"y":221.895263671875},{"x":151.4950714111328,"y":222.20938110351562},{"x":179.139404296875,"y":222.911376953125},{"x":207.11436462402344,"y":223.82569885253906},{"x":235.21751403808594,"y":224.1892852783203},{"x":262.92578125,"y":224.84408569335938},{"x":290.8519592285156,"y":225.4759521484375},{"x":318.79962158203125,"y":225.90077209472656},{"x":346.38800048828125,"y":226.4027557373047},{"x":374.32354736328125,"y":227.16883850097656},{"x":402.0463562011719,"y":227.84994506835938},{"x":36.89753341674805,"y":246.89064025878906},{"x":64.67141723632812,"y":247.58096313476562},{"x":92.54451751708984,"y":248.107421875},{"x":120.65547180175781,"y":248.49281311035156},{"x":148.72691345214844,"y":249.0157470703125},{"x":176.9605255126953,"y":249.70095825195312},{"x":205.07650756835938,"y":250.2705078125},{"x":233.1544952392578,"y":250.8683624267578},{"x":261.18035888671875,"y":251.38487243652344},{"x":289.1529846191406,"y":252.13197326660156},{"x":317.45166015625,"y":252.49880981445312},{"x":345.3446350097656,"y":253.18179321289062},{"x":373.5143127441406,"y":253.87200927734375},{"x":401.45892333984375,"y":254.4607391357422}],"reprojectionErrors":[{"x":-0.2610931396484375,"y":-0.10062408447265625},{"x":-0.257843017578125,"y":0.0511016845703125},{"x":0.02392578125,"y":-0.07644462585449219},{"x":-0.170928955078125,"y":-0.1409320831298828},{"x":0.152069091796875,"y":-0.055202484130859375},{"x":-0.2457275390625,"y":0.0862274169921875},{"x":-0.5576553344726562,"y":-0.3542671203613281},{"x":-0.43392181396484375,"y":-0.4049873352050781},{"x":0.03701019287109375,"y":0.14023208618164062},{"x":0.3018035888671875,"y":0.19143295288085938},{"x":0.1780242919921875,"y":-0.17259597778320312},{"x":-0.19000244140625,"y":-0.06460952758789062},{"x":-0.044708251953125,"y":-0.19884109497070312},{"x":-0.150543212890625,"y":-0.362396240234375},{"x":-0.062957763671875,"y":0.10152053833007812},{"x":-0.049652099609375,"y":-0.011241912841796875},{"x":-0.21771621704101562,"y":-0.5654296875},{"x":-0.1780242919921875,"y":-0.0583953857421875},{"x":0.026123046875,"y":-0.45355987548828125},{"x":0.029693603515625,"y":0.12487030029296875},{"x":-0.28912353515625,"y":-0.2095489501953125},{"x":-0.01568603515625,"y":-0.10762786865234375},{"x":0.03228759765625,"y":-0.16788482666015625},{"x":-0.054168701171875,"y":-0.1798248291015625},{"x":-0.2171630859375,"y":-0.1458282470703125},{"x":0.097259521484375,"y":-0.2051544189453125},{"x":-0.09792327880859375,"y":-0.39720916748046875},{"x":0.31951141357421875,"y":-0.20328521728515625},{"x":0.13140869140625,"y":-0.222991943359375},{"x":-0.057403564453125,"y":-0.01384735107421875},{"x":0.0405120849609375,"y":-0.460174560546875},{"x":0.071136474609375,"y":-0.36661529541015625},{"x":-0.2518310546875,"y":-0.16583251953125},{"x":-0.3632049560546875,"y":-0.46082305908203125},{"x":-0.089813232421875,"y":0.0096588134765625},{"x":-0.022186279296875,"y":-0.0644989013671875},{"x":-0.343505859375,"y":-0.35083770751953125},{"x":0.05096435546875,"y":-0.36946868896484375},{"x":0.056854248046875,"y":-0.10589599609375},{"x":0.33160400390625,"y":-0.3946075439453125},{"x":-0.09271240234375,"y":-0.1957550048828125},{"x":0.02223968505859375,"y":0.22037506103515625},{"x":-0.0124969482421875,"y":0.03032684326171875},{"x":0.0522918701171875,"y":-0.3339080810546875},{"x":0.1259613037109375,"y":-0.38175201416015625},{"x":-0.296173095703125,"y":-0.14227294921875},{"x":-0.2809600830078125,"y":-0.1083526611328125},{"x":-0.380889892578125,"y":-0.3523712158203125},{"x":0.057464599609375,"y":-0.08756256103515625},{"x":-0.159088134765625,"y":-0.2261962890625},{"x":-0.2391357421875,"y":-0.30881500244140625},{"x":-0.15740966796875,"y":-0.28653717041015625},{"x":0.185394287109375,"y":-0.21453094482421875},{"x":0.130615234375,"y":-0.20864105224609375},{"x":0.022686004638671875,"y":-0.328521728515625},{"x":0.09476470947265625,"y":-0.2518463134765625},{"x":0.03350067138671875,"y":-0.1319732666015625},{"x":0.0428924560546875,"y":-0.354644775390625},{"x":0.222320556640625,"y":-0.2749481201171875},{"x":-0.1844024658203125,"y":-0.2247772216796875},{"x":-0.25213623046875,"y":0.122833251953125},{"x":-0.3501129150390625,"y":-0.21563720703125},{"x":-0.096893310546875,"y":-0.168365478515625},{"x":-0.131011962890625,"y":-0.446929931640625},{"x":0.01043701171875,"y":-0.2706298828125},{"x":0.04437255859375,"y":-0.426727294921875},{"x":0.1666259765625,"y":-0.04376220703125},{"x":0.1302490234375,"y":-0.1832733154296875},{"x":-0.07432937622070312,"y":-0.23779296875},{"x":0.08061981201171875,"y":-0.1718902587890625},{"x":0.129364013671875,"y":-0.2709197998046875},{"x":0.1801605224609375,"y":-0.1424713134765625},{"x":0.2063446044921875,"y":-0.3824462890625},{"x":-0.046051025390625,"y":0.0501708984375},{"x":-0.334014892578125,"y":-0.301361083984375},{"x":-0.23651123046875,"y":-0.028167724609375},{"x":-0.399749755859375,"y":-0.36456298828125},{"x":-0.143280029296875,"y":-0.238861083984375},{"x":-0.132598876953125,"y":-0.31201171875},{"x":-0.179168701171875,"y":-0.18988037109375},{"x":0.07659912109375,"y":-0.41717529296875},{"x":0.263519287109375,"y":-0.0877227783203125},{"x":-0.0025482177734375,"y":0.0618743896484375},{"x":0.1414947509765625,"y":0.04443359375},{"x":0.12099456787109375,"y":0.2074737548828125},{"x":-0.1868743896484375,"y":-0.18231201171875},{"x":7.476806640625E-4,"y":0.1168975830078125},{"x":-0.1552276611328125,"y":-0.0988616943359375},{"x":-0.263702392578125,"y":-0.0391082763671875},{"x":-0.2180023193359375,"y":-0.0969696044921875},{"x":-0.215606689453125,"y":0.014190673828125},{"x":-0.093719482421875,"y":-0.17132568359375},{"x":-0.23846435546875,"y":-0.3313446044921875},{"x":-0.0032958984375,"y":-0.093170166015625},{"x":0.0924072265625,"y":-0.133087158203125},{"x":-0.00250244140625,"y":-0.045196533203125},{"x":-0.08882904052734375,"y":0.0223236083984375},{"x":0.06369781494140625,"y":-0.0284881591796875},{"x":-0.03592681884765625,"y":0.05609130859375},{"x":-0.159576416015625,"y":0.0632476806640625},{"x":-0.094970703125,"y":0.2822113037109375},{"x":0.047821044921875,"y":0.1215972900390625},{"x":-0.1101837158203125,"y":-0.2431182861328125},{"x":-0.369293212890625,"y":-0.04888916015625},{"x":-0.2091064453125,"y":-0.137725830078125},{"x":-0.24517822265625,"y":-0.195526123046875},{"x":-0.2838134765625,"y":-0.0382232666015625},{"x":0.05303955078125,"y":0.0499114990234375},{"x":0.056182861328125,"y":-0.11810302734375},{"x":0.282745361328125,"y":-0.1932525634765625},{"x":0.057071685791015625,"y":0.1640777587890625},{"x":0.15869903564453125,"y":0.0010223388671875},{"x":0.202362060546875,"y":0.009429931640625},{"x":0.04671478271484375,"y":0.1664886474609375},{"x":-0.033599853515625,"y":0.1935272216796875},{"x":-0.24298095703125,"y":0.065765380859375},{"x":-0.3043975830078125,"y":0.0611114501953125},{"x":-0.3002166748046875,"y":0.035552978515625},{"x":-0.219085693359375,"y":0.0986785888671875},{"x":-0.062652587890625,"y":-0.0615081787109375},{"x":-0.212982177734375,"y":0.16583251953125},{"x":0.058868408203125,"y":0.084197998046875},{"x":0.06768798828125,"y":0.0024566650390625},{"x":0.3125,"y":0.029296875}],"optimisedCameraToObject":{"translation":{"x":-0.1875583146948461,"y":-0.16915530841882517,"z":0.39260800066116563},"rotation":{"quaternion":{"W":0.994526623335192,"X":-0.10385776089745864,"Y":0.003060408319193511,"Z":0.010999767260589648}}},"cornersUsed":[false,false,true,true,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,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,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":"img2.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img2.png"},{"locationInObjectSpace":[{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":621.972900390625,"y":22.346355438232422},{"x":648.3125610351562,"y":24.15988540649414},{"x":674.7293090820312,"y":26.137088775634766},{"x":700.8054809570312,"y":27.960508346557617},{"x":353.7774963378906,"y":26.70035171508789},{"x":380.7215270996094,"y":28.475584030151367},{"x":407.674072265625,"y":30.4617919921875},{"x":434.6341247558594,"y":32.28974533081055},{"x":461.7198181152344,"y":33.988040924072266},{"x":488.68609619140625,"y":36.028099060058594},{"x":515.3353881835938,"y":37.746681213378906},{"x":542.6226196289062,"y":39.57954788208008},{"x":569.0643310546875,"y":41.73627853393555},{"x":596.1466674804688,"y":43.51663589477539},{"x":622.8809204101562,"y":45.241249084472656},{"x":649.3277587890625,"y":47.274898529052734},{"x":676.1405639648438,"y":49.06367111206055},{"x":702.4314575195312,"y":50.92975616455078},{"x":351.7895202636719,"y":50.3086051940918},{"x":379.0108947753906,"y":52.0494270324707},{"x":406.431396484375,"y":54.016815185546875},{"x":433.8346862792969,"y":55.74766540527344},{"x":460.927734375,"y":57.54561233520508},{"x":488.136474609375,"y":59.51274108886719},{"x":515.1572875976562,"y":61.26607894897461},{"x":542.4171752929688,"y":63.065895080566406},{"x":569.3115234375,"y":65.2979507446289},{"x":596.49560546875,"y":66.96638488769531},{"x":623.5594482421875,"y":68.96818542480469},{"x":650.7101440429688,"y":70.5947036743164},{"x":676.9871215820312,"y":72.21996307373047},{"x":704.2664794921875,"y":74.49109649658203},{"x":349.823486328125,"y":74.30413055419922},{"x":377.2451171875,"y":76.22576141357422},{"x":404.9816589355469,"y":77.95940399169922},{"x":432.4344787597656,"y":79.76702117919922},{"x":459.94049072265625,"y":81.57991790771484},{"x":487.47705078125,"y":83.47085571289062},{"x":514.7877197265625,"y":85.06768035888672},{"x":542.338623046875,"y":87.20939636230469},{"x":569.724853515625,"y":88.99850463867188},{"x":596.9700927734375,"y":90.99762725830078},{"x":624.4115600585938,"y":92.65794372558594},{"x":651.7570190429688,"y":94.85884094238281},{"x":678.9412231445312,"y":96.68376159667969},{"x":706.03369140625,"y":98.27079772949219},{"x":347.992431640625,"y":98.89391326904297},{"x":375.7752990722656,"y":100.43009948730469},{"x":403.75372314453125,"y":102.33873748779297},{"x":431.35137939453125,"y":104.19725036621094},{"x":459.118408203125,"y":106.11153411865234},{"x":486.8695373535156,"y":107.98677825927734},{"x":514.519775390625,"y":109.64347839355469},{"x":542.3770141601562,"y":111.63542938232422},{"x":569.8309326171875,"y":113.55773162841797},{"x":597.7249755859375,"y":115.26783752441406},{"x":625.0179443359375,"y":117.29618835449219},{"x":652.6773071289062,"y":118.892333984375},{"x":680.3698120117188,"y":120.93228912353516},{"x":707.8525390625,"y":122.94837188720703},{"x":345.8616027832031,"y":123.61595153808594},{"x":373.9356994628906,"y":125.46063232421875},{"x":402.08270263671875,"y":127.39042663574219},{"x":430.2409362792969,"y":129.28713989257812},{"x":458.1880187988281,"y":130.97738647460938},{"x":486.2271423339844,"y":132.98477172851562},{"x":514.0482788085938,"y":134.7856903076172},{"x":542.2747192382812,"y":136.62356567382812},{"x":570.3123168945312,"y":138.412353515625},{"x":598.3104248046875,"y":140.2166290283203},{"x":626.0426025390625,"y":142.07386779785156},{"x":654.0311279296875,"y":143.9366455078125},{"x":681.8047485351562,"y":145.7411651611328},{"x":709.4666748046875,"y":147.94456481933594},{"x":343.89764404296875,"y":148.93585205078125},{"x":372.26898193359375,"y":151.1259765625},{"x":400.7958679199219,"y":152.9500732421875},{"x":429.0482177734375,"y":154.81736755371094},{"x":457.23834228515625,"y":156.74526977539062},{"x":485.8371276855469,"y":158.4000244140625},{"x":513.9227294921875,"y":160.23757934570312},{"x":542.2553100585938,"y":162.04241943359375},{"x":570.5614013671875,"y":164.03106689453125},{"x":598.8704223632812,"y":165.97048950195312},{"x":627.015380859375,"y":167.75070190429688},{"x":655.130126953125,"y":169.62158203125},{"x":683.3973388671875,"y":171.36158752441406},{"x":711.3294067382812,"y":173.00729370117188},{"x":341.8562927246094,"y":175.06947326660156},{"x":370.500732421875,"y":176.86834716796875},{"x":399.140380859375,"y":178.74281311035156},{"x":427.89483642578125,"y":180.76528930664062},{"x":456.3167419433594,"y":182.49232482910156},{"x":485.2734375,"y":184.43873596191406},{"x":513.6571044921875,"y":186.13363647460938},{"x":542.1946411132812,"y":188.0939178466797},{"x":570.8513793945312,"y":189.9541015625},{"x":599.485107421875,"y":191.793701171875},{"x":627.9644775390625,"y":193.6223602294922},{"x":656.4376220703125,"y":195.55804443359375},{"x":684.914794921875,"y":197.31875610351562},{"x":713.3458251953125,"y":199.35885620117188},{"x":339.64801025390625,"y":201.6026611328125},{"x":368.7658996582031,"y":203.4286346435547},{"x":397.7966613769531,"y":205.3266143798828},{"x":426.7207336425781,"y":207.11463928222656},{"x":455.7086486816406,"y":209.07675170898438},{"x":484.4462585449219,"y":211.11032104492188},{"x":513.2127075195312,"y":212.82000732421875},{"x":542.3628540039062,"y":214.7144012451172},{"x":571.2296752929688,"y":216.45181274414062},{"x":600.2088012695312,"y":218.42276000976562},{"x":629.0075073242188,"y":220.18988037109375},{"x":657.7457275390625,"y":222.1202392578125},{"x":686.614990234375,"y":224.08287048339844},{"x":715.2051391601562,"y":225.9145050048828},{"x":337.3204345703125,"y":228.81764221191406},{"x":366.7921447753906,"y":230.60845947265625},{"x":395.96844482421875,"y":232.38380432128906},{"x":425.3614501953125,"y":234.2249755859375},{"x":454.487060546875,"y":236.1088104248047},{"x":483.97039794921875,"y":238.0100860595703},{"x":513.0639038085938,"y":239.90084838867188},{"x":542.4448852539062,"y":241.8563690185547},{"x":571.4730224609375,"y":243.66600036621094},{"x":600.6976928710938,"y":245.58106994628906},{"x":629.8167724609375,"y":247.3704833984375},{"x":659.2215576171875,"y":249.23114013671875},{"x":688.2348022460938,"y":251.21157836914062},{"x":717.198486328125,"y":253.14157104492188}],"reprojectionErrors":[{"x":0.2567138671875,"y":-0.07818603515625},{"x":-0.1748046875,"y":-0.07644271850585938},{"x":0.20123291015625,"y":-0.3864250183105469},{"x":-0.103759765625,"y":-0.3080940246582031},{"x":-0.103515625,"y":-0.16227340698242188},{"x":0.138916015625,"y":-0.3139495849609375},{"x":-0.03228759765625,"y":-0.20940399169921875},{"x":0.2684326171875,"y":-0.17103195190429688},{"x":0.072509765625,"y":0.04480743408203125},{"x":0.161773681640625,"y":0.07030105590820312},{"x":0.02850341796875,"y":-0.11811447143554688},{"x":-0.113555908203125,"y":-0.05751800537109375},{"x":0.02606201171875,"y":-0.05173492431640625},{"x":0.018890380859375,"y":-0.20303726196289062},{"x":0.166015625,"y":-0.12865066528320312},{"x":0.03790283203125,"y":-0.08903121948242188},{"x":0.2366943359375,"y":-0.4701385498046875},{"x":0.1044921875,"y":-0.27630615234375},{"x":0.0489501953125,"y":-0.40473175048828125},{"x":-0.13958740234375,"y":-0.14694976806640625},{"x":0.4969482421875,"y":0.12279510498046875},{"x":0.08013916015625,"y":-0.24282073974609375},{"x":0.060089111328125,"y":-0.041961669921875},{"x":0.2347412109375,"y":-0.18872833251953125},{"x":0.07061767578125,"y":-0.135498046875},{"x":0.163726806640625,"y":-0.1444091796875},{"x":0.174560546875,"y":-0.14696502685546875},{"x":0.123138427734375,"y":-0.21611785888671875},{"x":0.26336669921875,"y":0.02010345458984375},{"x":0.12646484375,"y":-0.27751922607421875},{"x":0.11480712890625,"y":-0.211669921875},{"x":0.2021484375,"y":-0.3451690673828125},{"x":0.04876708984375,"y":-0.1294097900390625},{"x":-0.0556640625,"y":-0.44396209716796875},{"x":-0.04833984375,"y":-0.37248992919921875},{"x":-0.0013427734375,"y":-0.05327606201171875},{"x":-0.129364013671875,"y":-0.22486114501953125},{"x":-0.023895263671875,"y":0.02236175537109375},{"x":-0.13824462890625,"y":-0.09152984619140625},{"x":0.101165771484375,"y":-0.14414215087890625},{"x":0.141571044921875,"y":-0.2415618896484375},{"x":0.16552734375,"y":-0.2891693115234375},{"x":0.2554931640625,"y":-0.107666015625},{"x":0.10076904296875,"y":-0.25103759765625},{"x":0.30926513671875,"y":-0.3145751953125},{"x":0.0347900390625,"y":-0.15594482421875},{"x":0.31597900390625,"y":-0.30577850341796875},{"x":0.18280029296875,"y":-0.01383209228515625},{"x":-0.03399658203125,"y":-0.1563262939453125},{"x":-0.0941162109375,"y":-0.26578521728515625},{"x":-0.062591552734375,"y":-0.0248260498046875},{"x":0.050445556640625,"y":-0.0775604248046875},{"x":0.0657958984375,"y":-0.20477294921875},{"x":0.04241943359375,"y":-0.2884521484375},{"x":0.199981689453125,"y":-0.1554107666015625},{"x":0.2325439453125,"y":-0.3294525146484375},{"x":0.44744873046875,"y":-0.28717041015625},{"x":0.21868896484375,"y":-0.2721710205078125},{"x":0.1378173828125,"y":-0.1986236572265625},{"x":0.052734375,"y":-0.1313018798828125},{"x":0.18731689453125,"y":-0.1078643798828125},{"x":0.0166015625,"y":-0.08111572265625},{"x":0.00921630859375,"y":0.012542724609375},{"x":0.0594482421875,"y":-0.28424072265625},{"x":-0.20770263671875,"y":0.110382080078125},{"x":-0.086212158203125,"y":-0.2792816162109375},{"x":-0.145538330078125,"y":-0.292999267578125},{"x":0.0416259765625,"y":-0.3402252197265625},{"x":0.26019287109375,"y":-0.4385223388671875},{"x":0.0364990234375,"y":-0.254364013671875},{"x":0.28961181640625,"y":-0.243896484375},{"x":0.2567138671875,"y":-0.1917877197265625},{"x":0.2083740234375,"y":-0.31475830078125},{"x":0.11260986328125,"y":-0.3799896240234375},{"x":0.1336669921875,"y":-0.2776947021484375},{"x":0.135009765625,"y":-0.257965087890625},{"x":-0.0687255859375,"y":-0.0994415283203125},{"x":0.0074462890625,"y":0.16107177734375},{"x":-0.322021484375,"y":-0.01641845703125},{"x":-0.160797119140625,"y":-0.0063323974609375},{"x":-0.02056884765625,"y":-0.0626983642578125},{"x":-0.023712158203125,"y":-0.2581329345703125},{"x":0.27423095703125,"y":-0.1493988037109375},{"x":0.00311279296875,"y":-0.251495361328125},{"x":0.2679443359375,"y":-0.0937347412109375},{"x":0.3389892578125,"y":-0.193206787109375},{"x":0.24810791015625,"y":-0.1846466064453125},{"x":0.13482666015625,"y":-0.14776611328125},{"x":0.127685546875,"y":-0.0924224853515625},{"x":0.0758056640625,"y":-0.1367645263671875},{"x":-0.0338134765625,"y":9.918212890625E-4},{"x":-0.1536865234375,"y":-0.13372802734375},{"x":-0.317626953125,"y":0.028472900390625},{"x":-0.309661865234375,"y":0.0199432373046875},{"x":-0.24078369140625,"y":-0.0522918701171875},{"x":-0.09442138671875,"y":-0.0064239501953125},{"x":-0.043975830078125,"y":-0.1267242431640625},{"x":0.2218017578125,"y":-0.3107452392578125},{"x":0.4208984375,"y":-0.163360595703125},{"x":0.195556640625,"y":-0.1933441162109375},{"x":0.2099609375,"y":-0.059234619140625},{"x":0.065673828125,"y":-0.1517333984375},{"x":0.05255126953125,"y":-0.03369140625},{"x":0.04791259765625,"y":-0.0723724365234375},{"x":-0.142578125,"y":-0.13702392578125},{"x":-0.111572265625,"y":-0.0645751953125},{"x":-0.243927001953125,"y":-0.01666259765625},{"x":-0.261871337890625,"y":0.01837158203125},{"x":-0.01116943359375,"y":0.0763702392578125},{"x":-0.0069580078125,"y":0.0758209228515625},{"x":0.231903076171875,"y":0.0396881103515625},{"x":0.077362060546875,"y":-0.00701904296875},{"x":0.27398681640625,"y":-0.0365142822265625},{"x":0.14154052734375,"y":-0.1243133544921875},{"x":0.3175048828125,"y":-0.0599365234375},{"x":0.24951171875,"y":-0.094940185546875},{"x":0.23681640625,"y":0.0015869140625},{"x":-0.11468505859375,"y":0.0325164794921875},{"x":-0.130615234375,"y":-0.0508880615234375},{"x":-0.15576171875,"y":-0.0785980224609375}],"optimisedCameraToObject":{"translation":{"x":-0.02107205416203958,"y":-0.1747896557261308,"z":0.38192386828638925},"rotation":{"quaternion":{"W":0.9910023406203294,"X":-0.1299808379566844,"Y":-0.011641493960562643,"Z":0.02972908117438092}}},"cornersUsed":[false,false,false,false,false,false,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,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,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],"snapshotName":"img3.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img3.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":335.61114501953125,"y":213.72145080566406},{"x":366.7873229980469,"y":215.73773193359375},{"x":398.0549011230469,"y":217.8726806640625},{"x":429.2989807128906,"y":219.852783203125},{"x":460.65740966796875,"y":222.03897094726562},{"x":492.302490234375,"y":224.17782592773438},{"x":523.6226806640625,"y":226.47991943359375},{"x":555.3649291992188,"y":228.40087890625},{"x":587.05126953125,"y":230.69412231445312},{"x":619.0450439453125,"y":232.97219848632812},{"x":650.8630981445312,"y":235.10797119140625},{"x":682.97314453125,"y":237.1912841796875},{"x":714.9637451171875,"y":239.51011657714844},{"x":746.9963989257812,"y":241.67388916015625},{"x":333.0701904296875,"y":243.8075714111328},{"x":364.2210693359375,"y":246.14990234375},{"x":395.7177734375,"y":248.1679229736328},{"x":427.3415222167969,"y":250.32034301757812},{"x":458.7337341308594,"y":252.3231201171875},{"x":490.70166015625,"y":254.86419677734375},{"x":522.3569946289062,"y":257.0145568847656},{"x":554.2662963867188,"y":259.13946533203125},{"x":586.246337890625,"y":261.3533630371094},{"x":618.3025512695312,"y":263.8031921386719},{"x":650.5922241210938,"y":265.8831481933594},{"x":682.9202270507812,"y":268.1812744140625},{"x":715.212646484375,"y":270.3765563964844},{"x":747.5728149414062,"y":272.85858154296875},{"x":330.2361755371094,"y":274.5447998046875},{"x":361.4858093261719,"y":276.4276428222656},{"x":393.3501281738281,"y":278.923828125},{"x":425.2797546386719,"y":281.2822570800781},{"x":456.89593505859375,"y":283.3934326171875},{"x":488.9995422363281,"y":285.4730529785156},{"x":520.9071655273438,"y":288.0560607910156},{"x":553.1390991210938,"y":290.078857421875},{"x":585.336181640625,"y":292.365234375},{"x":617.7391967773438,"y":294.73333740234375},{"x":650.248046875,"y":297.14556884765625},{"x":682.8099365234375,"y":299.38726806640625},{"x":715.4302368164062,"y":301.66729736328125},{"x":747.9988403320312,"y":304.0509948730469},{"x":327.14990234375,"y":305.8038024902344},{"x":359.1300964355469,"y":307.8442687988281},{"x":391.1134948730469,"y":310.0694274902344},{"x":423.002197265625,"y":312.4560241699219},{"x":455.1221618652344,"y":314.7569274902344},{"x":487.393798828125,"y":316.9876403808594},{"x":519.5082397460938,"y":319.302490234375},{"x":552.0994262695312,"y":321.8071594238281},{"x":584.531982421875,"y":324.1225280761719},{"x":617.2045288085938,"y":326.3804626464844},{"x":649.6935424804688,"y":328.5424499511719},{"x":682.7509765625,"y":331.3050842285156},{"x":715.723876953125,"y":333.661376953125},{"x":748.3713989257812,"y":336.1308898925781},{"x":324.2710876464844,"y":337.296875},{"x":356.349609375,"y":339.8482971191406},{"x":388.5138854980469,"y":341.9437561035156},{"x":420.89727783203125,"y":344.1116638183594},{"x":453.19293212890625,"y":346.645751953125},{"x":485.8007507324219,"y":348.94952392578125},{"x":518.2705688476562,"y":351.3009338378906},{"x":550.85693359375,"y":353.66876220703125},{"x":583.6077270507812,"y":356.2791748046875},{"x":616.596435546875,"y":358.6239013671875},{"x":649.8145141601562,"y":361.00921630859375},{"x":682.7877197265625,"y":363.6954345703125},{"x":716.00927734375,"y":365.77508544921875},{"x":748.8948364257812,"y":368.24468994140625},{"x":321.2893981933594,"y":369.3394775390625},{"x":353.8073425292969,"y":371.7357482910156},{"x":385.9826354980469,"y":374.0289611816406},{"x":418.74639892578125,"y":376.4033203125},{"x":451.2976989746094,"y":378.9160461425781},{"x":484.0147399902344,"y":381.40399169921875},{"x":516.6596069335938,"y":383.5796203613281},{"x":549.9617309570312,"y":386.40985107421875},{"x":582.9321899414062,"y":388.8545837402344},{"x":616.2857055664062,"y":391.2784729003906},{"x":649.5155639648438,"y":393.9898986816406},{"x":682.7084350585938,"y":396.2173156738281},{"x":715.9568481445312,"y":398.8262634277344},{"x":749.5191040039062,"y":401.5934753417969},{"x":318.3018493652344,"y":402.25244140625},{"x":350.9263916015625,"y":404.4854431152344},{"x":383.803955078125,"y":407.1091613769531},{"x":416.3841552734375,"y":409.24639892578125},{"x":449.2740783691406,"y":411.9874572753906},{"x":482.48681640625,"y":414.60882568359375},{"x":515.6408081054688,"y":416.9619445800781},{"x":548.950439453125,"y":419.6076354980469},{"x":582.2005004882812,"y":422.08758544921875},{"x":615.7579956054688,"y":424.9231262207031},{"x":649.1868896484375,"y":427.3318786621094},{"x":682.7678833007812,"y":429.8159484863281},{"x":716.3390502929688,"y":432.6656799316406},{"x":749.94921875,"y":434.8578186035156},{"x":315.0951232910156,"y":435.405517578125},{"x":348.077880859375,"y":438.055908203125},{"x":381.1894226074219,"y":440.7335510253906},{"x":414.2456359863281,"y":442.98443603515625},{"x":447.3365478515625,"y":445.3221435546875},{"x":480.88641357421875,"y":447.9966735839844},{"x":514.1296997070312,"y":450.7013854980469},{"x":547.9049682617188,"y":453.3445129394531},{"x":581.21484375,"y":455.8226318359375},{"x":615.0870361328125,"y":458.6698913574219},{"x":648.8471069335938,"y":461.05499267578125},{"x":682.6784057617188,"y":464.12286376953125},{"x":716.6701049804688,"y":466.4396667480469},{"x":750.7378540039062,"y":469.1604309082031},{"x":311.9043884277344,"y":469.5910949707031},{"x":345.2185974121094,"y":472.111328125},{"x":378.6648254394531,"y":474.6033020019531},{"x":412.07464599609375,"y":477.2489929199219},{"x":445.50714111328125,"y":479.8984375},{"x":479.17236328125,"y":482.4314880371094},{"x":512.8706665039062,"y":485.1347961425781},{"x":546.9691162109375,"y":487.88543701171875},{"x":580.6317138671875,"y":490.53131103515625},{"x":614.4957275390625,"y":493.03729248046875},{"x":648.7035522460938,"y":495.99993896484375},{"x":683.0497436523438,"y":498.62750244140625},{"x":717.066650390625,"y":501.3738708496094},{"x":751.1130981445312,"y":503.791748046875},{"x":308.59527587890625,"y":504.1800842285156},{"x":342.3722229003906,"y":506.8631896972656},{"x":375.9268798828125,"y":509.3532409667969},{"x":409.6550598144531,"y":511.94293212890625},{"x":443.1678161621094,"y":514.2824096679688},{"x":477.5260925292969,"y":517.42138671875},{"x":511.4052429199219,"y":520.1531982421875},{"x":545.9005737304688,"y":522.836181640625},{"x":579.9013671875,"y":525.6176147460938},{"x":614.4322509765625,"y":528.4273071289062},{"x":648.6119384765625,"y":531.2615356445312},{"x":683.0765991210938,"y":534.106201171875},{"x":717.3336791992188,"y":536.4866333007812},{"x":751.756103515625,"y":539.2854614257812}],"reprojectionErrors":[{"x":0.173309326171875,"y":-7.62939453125E-4},{"x":0.146575927734375,"y":0.0509490966796875},{"x":0.119293212890625,"y":-0.001708984375},{"x":0.203216552734375,"y":0.114593505859375},{"x":0.25738525390625,"y":0.03875732421875},{"x":0.106292724609375,"y":0.024017333984375},{"x":0.35833740234375,"y":-0.1403656005859375},{"x":0.26324462890625,"y":0.0897674560546875},{"x":0.2957763671875,"y":-0.0391845703125},{"x":0.0892333984375,"y":-0.13995361328125},{"x":0.12353515625,"y":-0.085601806640625},{"x":-0.07257080078125,"y":0.0337982177734375},{"x":-0.09088134765625,"y":-0.069915771484375},{"x":-0.09637451171875,"y":-0.006378173828125},{"x":-0.126708984375,"y":0.05029296875},{"x":0.121856689453125,"y":-0.16302490234375},{"x":0.11700439453125,"y":-0.03857421875},{"x":0.074310302734375,"y":-0.035247802734375},{"x":0.3492431640625,"y":0.13079833984375},{"x":0.13128662109375,"y":-0.228546142578125},{"x":0.30548095703125,"y":-0.184478759765625},{"x":0.302001953125,"y":-0.10247802734375},{"x":0.30072021484375,"y":-0.09716796875},{"x":0.29290771484375,"y":-0.315673828125},{"x":0.11785888671875,"y":-0.152435302734375},{"x":-0.03271484375,"y":-0.195709228515625},{"x":-0.08843994140625,"y":-0.12469482421875},{"x":-0.156005859375,"y":-0.329193115234375},{"x":-0.181610107421875,"y":-0.057586669921875},{"x":0.222808837890625,"y":0.25140380859375},{"x":0.10650634765625,"y":-0.0404052734375},{"x":0.015716552734375,"y":-0.182037353515625},{"x":0.325927734375,"y":-0.064208984375},{"x":0.233001708984375,"y":0.09716796875},{"x":0.41705322265625,"y":-0.233062744140625},{"x":0.35443115234375,"y":0.00848388671875},{"x":0.40087890625,"y":-0.002197265625},{"x":0.31231689453125,"y":-0.08343505859375},{"x":0.185302734375,"y":-0.197906494140625},{"x":0.0692138671875,"y":-0.131134033203125},{"x":-0.044921875,"y":-0.09222412109375},{"x":-0.0504150390625,"y":-0.146759033203125},{"x":-0.033538818359375,"y":-0.181121826171875},{"x":-0.100372314453125,"y":0.03485107421875},{"x":-0.07476806640625,"y":0.07781982421875},{"x":0.137908935546875,"y":-0.029144287109375},{"x":0.20843505859375,"y":-0.039154052734375},{"x":0.213104248046875,"y":0.0321044921875},{"x":0.4573974609375,"y":0.03009033203125},{"x":0.303955078125,"y":-0.151153564453125},{"x":0.384765625,"y":-0.1326904296875},{"x":0.2977294921875,"y":-0.046630859375},{"x":0.46282958984375,"y":0.145294189453125},{"x":0.1246337890625,"y":-0.25372314453125},{"x":-0.06744384765625,"y":-0.2369384765625},{"x":0.123779296875,"y":-0.324188232421875},{"x":-0.143585205078125,"y":-0.018310546875},{"x":-0.044586181640625,"y":-0.246734619140625},{"x":0.06597900390625,"y":-0.008453369140625},{"x":0.051483154296875,"y":0.16796875},{"x":0.215423583984375,"y":-0.011474609375},{"x":0.154510498046875,"y":0.04949951171875},{"x":0.3155517578125,"y":0.07269287109375},{"x":0.44049072265625,"y":0.089111328125},{"x":0.47802734375,"y":-0.127655029296875},{"x":0.35107421875,"y":-0.069580078125},{"x":0.06463623046875,"y":-0.043212890625},{"x":0.08941650390625,"y":-0.309051513671875},{"x":-0.07147216796875,"y":0.0400390625},{"x":0.16265869140625,"y":0.00732421875},{"x":-0.202911376953125,"y":0.13043212890625},{"x":-0.274200439453125,"y":0.125640869140625},{"x":0.09625244140625,"y":0.2337646484375},{"x":-0.026031494140625,"y":0.27032470703125},{"x":0.156494140625,"y":0.1778564453125},{"x":0.26220703125,"y":0.119293212890625},{"x":0.5255126953125,"y":0.381927490234375},{"x":0.2135009765625,"y":-0.00146484375},{"x":0.31158447265625,"y":0.009033203125},{"x":0.10137939453125,"y":0.0484619140625},{"x":0.0860595703125,"y":-0.191802978515625},{"x":0.17529296875,"y":0.05950927734375},{"x":0.27288818359375,"y":-0.063385009765625},{"x":0.11676025390625,"y":-0.33746337890625},{"x":-0.30999755859375,"y":-0.040313720703125},{"x":-0.213592529296875,"y":0.18878173828125},{"x":-0.26934814453125,"y":0.035980224609375},{"x":0.06976318359375,"y":0.378265380859375},{"x":0.193145751953125,"y":0.12506103515625},{"x":0.084259033203125,"y":-3.662109375E-4},{"x":0.12115478515625,"y":0.150299072265625},{"x":0.08587646484375,"y":0.01593017578125},{"x":0.19000244140625,"y":0.054595947265625},{"x":0.06292724609375,"y":-0.25531005859375},{"x":0.136962890625,"y":-0.131683349609375},{"x":0.12774658203125,"y":-0.076904296875},{"x":0.19342041015625,"y":-0.381591796875},{"x":0.28143310546875,"y":-0.02276611328125},{"x":-0.25311279296875,"y":0.1158447265625},{"x":-0.2353515625,"y":2.74658203125E-4},{"x":-0.243682861328125,"y":-0.13470458984375},{"x":-0.097412109375,"y":0.16461181640625},{"x":0.109893798828125,"y":0.3843994140625},{"x":-0.04949951171875,"y":0.274383544921875},{"x":0.186279296875,"y":0.14093017578125},{"x":-0.02484130859375,"y":0.075531005859375},{"x":0.31072998046875,"y":0.18133544921875},{"x":0.16162109375,"y":-0.07611083984375},{"x":0.1986083984375,"y":0.13421630859375},{"x":0.2344970703125,"y":-0.3328857421875},{"x":0.17633056640625,"y":-0.043914794921875},{"x":0.10455322265625,"y":-0.154144287109375},{"x":-0.26904296875,"y":-0.176727294921875},{"x":-0.297760009765625,"y":-0.087188720703125},{"x":-0.3538818359375,"y":0.037384033203125},{"x":-0.27252197265625,"y":0.014739990234375},{"x":-0.11627197265625,"y":-0.00543212890625},{"x":-0.09881591796875,"y":0.096710205078125},{"x":-0.02410888671875,"y":0.034210205078125},{"x":-0.26300048828125,"y":-0.070281982421875},{"x":0.01690673828125,"y":-0.064971923828125},{"x":0.174560546875,"y":0.084991455078125},{"x":0.063720703125,"y":-0.21728515625},{"x":-0.114013671875,"y":-0.180328369140625},{"x":0.10516357421875,"y":-0.25836181640625},{"x":0.3585205078125,"y":-0.004364013671875},{"x":-0.225067138671875,"y":-0.2716064453125},{"x":-0.42596435546875,"y":-0.26763916015625},{"x":-0.298004150390625,"y":-0.06494140625},{"x":-0.2406005859375,"y":0.04351806640625},{"x":0.13165283203125,"y":0.40728759765625},{"x":-0.245941162109375,"y":-0.023681640625},{"x":-0.0523681640625,"y":-0.04302978515625},{"x":-0.38671875,"y":-0.00933837890625},{"x":-0.14202880859375,"y":-0.0701904296875},{"x":-0.34674072265625,"y":-0.15582275390625},{"x":-0.12353515625,"y":-0.26275634765625},{"x":-0.11236572265625,"y":-0.377197265625},{"x":0.17529296875,"y":-0.02484130859375},{"x":0.36260986328125,"y":-0.088623046875}],"optimisedCameraToObject":{"translation":{"x":-0.02761212470951645,"y":-0.04917927615432779,"z":0.3272562581441467},"rotation":{"quaternion":{"W":0.9952328569210355,"X":-0.089726582559497,"Y":0.009928852287260787,"Z":0.03690689338382717}}},"cornersUsed":[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,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],"snapshotName":"img4.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img4.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":105.97201538085938,"y":309.8360900878906},{"x":128.83383178710938,"y":310.0523986816406},{"x":152.0203094482422,"y":310.8271179199219},{"x":175.1244354248047,"y":311.06988525390625},{"x":198.3800811767578,"y":311.919677734375},{"x":221.9325408935547,"y":312.04510498046875},{"x":245.43740844726562,"y":312.933837890625},{"x":269.3026428222656,"y":313.46240234375},{"x":293.55169677734375,"y":314.0135498046875},{"x":317.33428955078125,"y":314.3710021972656},{"x":390.5801696777344,"y":316.2245788574219},{"x":415.1078186035156,"y":316.71636962890625},{"x":103.58958435058594,"y":333.7817687988281},{"x":126.58020782470703,"y":334.1640319824219},{"x":149.67039489746094,"y":334.6213684082031},{"x":173.01690673828125,"y":335.361328125},{"x":196.524658203125,"y":335.8681945800781},{"x":220.28526306152344,"y":336.4749755859375},{"x":244.01576232910156,"y":336.9942626953125},{"x":268.1405944824219,"y":337.5386962890625},{"x":291.90020751953125,"y":338.1139221191406},{"x":316.09368896484375,"y":338.9490661621094},{"x":340.4058532714844,"y":339.4774169921875},{"x":364.9822692871094,"y":340.1581115722656},{"x":389.5903625488281,"y":340.8974914550781},{"x":414.3083190917969,"y":341.4143981933594},{"x":101.42829895019531,"y":357.7365417480469},{"x":124.4046630859375,"y":357.9864501953125},{"x":147.706787109375,"y":358.6903381347656},{"x":171.4070281982422,"y":359.238037109375},{"x":194.9361572265625,"y":359.9873962402344},{"x":218.44757080078125,"y":360.4354248046875},{"x":242.42308044433594,"y":361.4734191894531},{"x":266.7003173828125,"y":361.9197692871094},{"x":290.7685546875,"y":362.7881164550781},{"x":314.9964904785156,"y":363.38983154296875},{"x":339.3170471191406,"y":364.1214599609375},{"x":364.0210266113281,"y":364.86083984375},{"x":388.826171875,"y":365.5028381347656},{"x":413.53619384765625,"y":366.4107360839844},{"x":99.06454467773438,"y":381.9368896484375},{"x":122.27204895019531,"y":382.51251220703125},{"x":145.85232543945312,"y":383.0697326660156},{"x":169.15719604492188,"y":383.86669921875},{"x":192.8909912109375,"y":384.2329406738281},{"x":216.9113006591797,"y":385.1613464355469},{"x":240.6796417236328,"y":385.8592834472656},{"x":264.7925109863281,"y":386.7747497558594},{"x":289.2093200683594,"y":387.5066223144531},{"x":313.60772705078125,"y":388.1920166015625},{"x":338.1781311035156,"y":389.32232666015625},{"x":362.9212951660156,"y":389.8410339355469},{"x":387.9782409667969,"y":390.7615966796875},{"x":412.68115234375,"y":391.7637939453125},{"x":96.75067138671875,"y":406.0673828125},{"x":120.06688690185547,"y":406.9586486816406},{"x":143.81954956054688,"y":407.69720458984375},{"x":167.26084899902344,"y":408.2733154296875},{"x":191.0171661376953,"y":409.26434326171875},{"x":214.9783477783203,"y":410.0098571777344},{"x":239.04945373535156,"y":410.9587707519531},{"x":263.6346435546875,"y":411.5241394042969},{"x":287.8003845214844,"y":412.6966857910156},{"x":312.2793273925781,"y":413.5916748046875},{"x":337.0002136230469,"y":414.1408996582031},{"x":361.88446044921875,"y":415.08984375},{"x":387.0273132324219,"y":416.083251953125},{"x":412.044921875,"y":416.9268493652344},{"x":94.31800079345703,"y":430.8633728027344},{"x":117.69237518310547,"y":431.42169189453125},{"x":141.3686065673828,"y":432.0939636230469},{"x":165.14451599121094,"y":433.3471374511719},{"x":188.87533569335938,"y":434.30413818359375},{"x":213.25421142578125,"y":435.09368896484375},{"x":237.28384399414062,"y":435.994140625},{"x":261.8209228515625,"y":437.0331726074219},{"x":286.2716369628906,"y":438.06182861328125},{"x":310.9524230957031,"y":438.8966369628906},{"x":335.964111328125,"y":439.89959716796875},{"x":360.6544189453125,"y":440.8049011230469},{"x":385.8089294433594,"y":441.6280212402344},{"x":411.12762451171875,"y":442.8293151855469},{"x":91.89552307128906,"y":455.95648193359375},{"x":115.10529327392578,"y":456.5415344238281},{"x":139.31178283691406,"y":457.82025146484375},{"x":162.8761444091797,"y":458.4855651855469},{"x":187.08226013183594,"y":459.60614013671875},{"x":211.24505615234375,"y":460.51702880859375},{"x":235.76873779296875,"y":461.6916198730469},{"x":260.2876281738281,"y":462.6510009765625},{"x":284.8896789550781,"y":463.6957092285156},{"x":309.6395568847656,"y":464.5657043457031},{"x":334.6051940917969,"y":465.6531677246094},{"x":359.66534423828125,"y":466.6297912597656},{"x":385.1003723144531,"y":467.80926513671875},{"x":410.2384338378906,"y":468.77728271484375},{"x":89.45352935791016,"y":480.8299560546875},{"x":113.0378189086914,"y":481.9710388183594},{"x":136.9707794189453,"y":483.0400695800781},{"x":160.90086364746094,"y":483.9735412597656},{"x":184.91799926757812,"y":485.05914306640625},{"x":209.22433471679688,"y":486.16510009765625},{"x":233.81915283203125,"y":487.0755615234375},{"x":258.6910400390625,"y":488.31219482421875},{"x":283.19610595703125,"y":489.4148864746094},{"x":308.3705139160156,"y":490.3665466308594},{"x":333.2748718261719,"y":491.7906799316406},{"x":358.2845153808594,"y":492.9864196777344},{"x":384.0488586425781,"y":494.01580810546875},{"x":409.4629211425781,"y":495.32470703125},{"x":86.99082946777344,"y":506.21539306640625},{"x":110.75772094726562,"y":507.81683349609375},{"x":134.4680633544922,"y":508.8521728515625},{"x":158.7787322998047,"y":509.98175048828125},{"x":183.00404357910156,"y":510.98199462890625},{"x":207.48968505859375,"y":512.054443359375},{"x":232.03131103515625,"y":513.4407348632812},{"x":256.9540710449219,"y":514.6099243164062},{"x":281.8907470703125,"y":515.7653198242188},{"x":306.7663269042969,"y":516.9559326171875},{"x":332.03350830078125,"y":518.24658203125},{"x":357.6214294433594,"y":519.4078979492188},{"x":383.1050720214844,"y":520.6659545898438},{"x":408.809814453125,"y":521.9009399414062},{"x":84.69329833984375,"y":532.1785888671875},{"x":108.21047973632812,"y":533.36865234375},{"x":132.1595916748047,"y":534.84814453125},{"x":156.43873596191406,"y":535.914306640625},{"x":180.8772735595703,"y":537.2173461914062},{"x":205.75047302246094,"y":538.2179565429688},{"x":230.1688690185547,"y":539.7840576171875},{"x":255.1297149658203,"y":541.00830078125},{"x":280.1507263183594,"y":542.335693359375},{"x":305.6374816894531,"y":543.4342651367188},{"x":330.8725280761719,"y":545.0786743164062},{"x":356.20294189453125,"y":546.2403564453125},{"x":381.9794006347656,"y":547.558349609375},{"x":407.9555358886719,"y":549.1118774414062}],"reprojectionErrors":[{"x":0.13555908203125,"y":0.125457763671875},{"x":0.0955047607421875,"y":0.38177490234375},{"x":-0.108184814453125,"y":0.085968017578125},{"x":-0.068817138671875,"y":0.328399658203125},{"x":-0.02069091796875,"y":-0.029876708984375},{"x":-0.1094970703125,"y":0.342529296875},{"x":0.0086822509765625,"y":-0.0419921875},{"x":-0.0745849609375,"y":-0.059967041015625},{"x":-0.383270263671875,"y":-0.094146728515625},{"x":-0.067657470703125,"y":0.07177734375},{"x":0.21649169921875,"y":-0.175048828125},{"x":0.15756988525390625,"y":-0.003082275390625},{"x":0.1617584228515625,"y":0.0999755859375},{"x":0.0719451904296875,"y":-0.07342529296875},{"x":-0.0171661376953125,"y":-0.00750732421875},{"x":-0.1976318359375,"y":-0.035308837890625},{"x":-0.186920166015625,"y":0.0306396484375},{"x":-0.40997314453125,"y":0.07763671875},{"x":-0.107757568359375,"y":0.10009765625},{"x":-0.079925537109375,"y":-0.131103515625},{"x":-0.011871337890625,"y":-0.04925537109375},{"x":-0.0498046875,"y":-0.11346435546875},{"x":0.038177490234375,"y":-0.230133056640625},{"x":0.1732177734375,"y":-0.118011474609375},{"x":0.0478515625,"y":-0.2412109375},{"x":0.11449432373046875,"y":0.1463623046875},{"x":0.01971435546875,"y":0.08599853515625},{"x":-0.3092041015625,"y":0.18792724609375},{"x":-0.30340576171875,"y":0.09429931640625},{"x":-0.1167144775390625,"y":0.308074951171875},{"x":-0.2313690185546875,"y":-0.06201171875},{"x":-0.485504150390625,"y":0.1656494140625},{"x":-0.368896484375,"y":-0.022613525390625},{"x":-0.250823974609375,"y":0.0618896484375},{"x":-0.064788818359375,"y":0.022552490234375},{"x":-0.102203369140625,"y":-0.018463134765625},{"x":-0.08148193359375,"y":0.04400634765625},{"x":0.192962646484375,"y":-0.1533203125},{"x":0.052734375,"y":-0.3048095703125},{"x":9.0789794921875E-4,"y":-0.157989501953125},{"x":-0.2576751708984375,"y":0.013214111328125},{"x":-0.075164794921875,"y":-0.049346923828125},{"x":-0.1562652587890625,"y":0.324798583984375},{"x":-0.3590087890625,"y":0.14276123046875},{"x":-0.14532470703125,"y":0.197174072265625},{"x":-0.112213134765625,"y":0.03997802734375},{"x":-0.219573974609375,"y":0.072357177734375},{"x":-0.145660400390625,"y":0.15716552734375},{"x":-0.0814208984375,"y":-0.197021484375},{"x":-0.02825927734375,"y":0.066314697265625},{"x":-0.12786865234375,"y":-0.0662841796875},{"x":0.286895751953125,"y":-0.274627685546875},{"x":-0.0217742919921875,"y":-0.045501708984375},{"x":-0.0682373046875,"y":-0.127593994140625},{"x":-0.3834075927734375,"y":-0.05108642578125},{"x":-0.219818115234375,"y":0.19378662109375},{"x":-0.204193115234375,"y":0.029571533203125},{"x":-0.2268218994140625,"y":0.11676025390625},{"x":-0.1931915283203125,"y":0.006378173828125},{"x":-0.5079345703125,"y":0.285400390625},{"x":-0.238006591796875,"y":-0.0369873046875},{"x":-0.116668701171875,"y":-0.07598876953125},{"x":-0.073211669921875,"y":0.236541748046875},{"x":-0.0296630859375,"y":0.15509033203125},{"x":-0.081939697265625,"y":0.034912109375},{"x":0.153106689453125,"y":0.07025146484375},{"x":-0.0075531005859375,"y":-0.193695068359375},{"x":0.0033111572265625,"y":0.145721435546875},{"x":-0.1181793212890625,"y":0.376983642578125},{"x":-0.170196533203125,"y":0.033172607421875},{"x":-0.0083160400390625,"y":-0.00872802734375},{"x":-0.3260955810546875,"y":0.12255859375},{"x":-0.1266937255859375,"y":0.148712158203125},{"x":-0.267242431640625,"y":0.041961669921875},{"x":-0.154449462890625,"y":-0.04876708984375},{"x":-0.10528564453125,"y":0.060028076171875},{"x":-0.22119140625,"y":0.00628662109375},{"x":0.149505615234375,"y":0.0557861328125},{"x":0.2205810546875,"y":0.193023681640625},{"x":0.29132080078125,"y":-0.042388916015625},{"x":-0.03417205810546875,"y":-0.375823974609375},{"x":0.25823974609375,"y":0.027252197265625},{"x":-0.2747955322265625,"y":-0.257568359375},{"x":0.0052642822265625,"y":0.076690673828125},{"x":-0.18585205078125,"y":-0.03863525390625},{"x":-0.1634521484375,"y":0.061370849609375},{"x":-0.3321685791015625,"y":-0.096710205078125},{"x":-0.326812744140625,"y":-0.03399658203125},{"x":-0.235809326171875,"y":-0.05108642578125},{"x":-0.1243896484375,"y":0.112030029296875},{"x":-0.06109619140625,"y":0.063140869140625},{"x":0.07476806640625,"y":0.1304931640625},{"x":0.00213623046875,"y":3.96728515625E-4},{"x":0.39215087890625,"y":0.08709716796875},{"x":-0.07251739501953125,"y":-0.0699462890625},{"x":-0.0362091064453125,"y":-0.13055419921875},{"x":-0.17547607421875,"y":-0.113433837890625},{"x":-0.13909912109375,"y":0.04486083984375},{"x":-0.0173492431640625,"y":0.05657958984375},{"x":-0.01275634765625,"y":0.053497314453125},{"x":-0.12506103515625,"y":0.25140380859375},{"x":-0.343292236328125,"y":0.128570556640625},{"x":-0.024078369140625,"y":0.145111083984375},{"x":-0.2041015625,"y":0.318023681640625},{"x":0.055450439453125,"y":0.023773193359375},{"x":0.37860107421875,"y":-0.036834716796875},{"x":0.115325927734375,"y":0.074127197265625},{"x":0.369873046875,"y":-0.089263916015625},{"x":-0.12200927734375,"y":-0.002227783203125},{"x":-0.14838409423828125,"y":-0.428863525390625},{"x":0.056732177734375,"y":-0.283843994140625},{"x":-0.163848876953125,"y":-0.227508544921875},{"x":-0.124786376953125,"y":-0.036346435546875},{"x":-0.1721649169921875,"y":0.0880126953125},{"x":-0.1020355224609375,"y":-0.09600830078125},{"x":-0.24005126953125,"y":-0.05767822265625},{"x":-0.219451904296875,"y":-2.44140625E-4},{"x":0.03424072265625,"y":0.02716064453125},{"x":0.067718505859375,"y":-0.040283203125},{"x":-0.048736572265625,"y":0.02667236328125},{"x":0.109222412109375,"y":0.001953125},{"x":0.215545654296875,"y":0.00531005859375},{"x":-0.36914825439453125,"y":-0.23291015625},{"x":-0.02436065673828125,"y":-0.15185546875},{"x":0.0653076171875,"y":-0.354736328125},{"x":0.0014801025390625,"y":-0.1387939453125},{"x":-0.045562744140625,"y":-0.154296875},{"x":-0.351470947265625,"y":0.137939453125},{"x":-0.0272064208984375,"y":-0.13006591796875},{"x":-0.0704498291015625,"y":-0.05096435546875},{"x":5.79833984375E-4,"y":-0.06988525390625},{"x":-0.220245361328125,"y":0.14508056640625},{"x":-0.0159912109375,"y":-0.18072509765625},{"x":0.265594482421875,"y":-0.0189208984375},{"x":0.273193359375,"y":-0.008544921875},{"x":0.252532958984375,"y":-0.2288818359375}],"optimisedCameraToObject":{"translation":{"x":-0.18106595801970743,"y":-0.003974438572380473,"z":0.4299125138025197},"rotation":{"quaternion":{"W":0.9961156325108365,"X":-0.07495371339134381,"Y":0.044015394812529446,"Z":0.014079507657645395}}},"cornersUsed":[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,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],"snapshotName":"img5.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img5.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5}],"locationInImageSpace":[{"x":64.60687255859375,"y":410.3379211425781},{"x":89.49788665771484,"y":409.4739685058594},{"x":114.56646728515625,"y":408.7121887207031},{"x":139.9454345703125,"y":408.0043640136719},{"x":165.15985107421875,"y":407.51959228515625},{"x":190.51539611816406,"y":406.7502746582031},{"x":215.822265625,"y":405.8276062011719},{"x":241.55105590820312,"y":404.9970703125},{"x":266.8352355957031,"y":404.26507568359375},{"x":292.27069091796875,"y":403.731201171875},{"x":317.9723815917969,"y":403.0228576660156},{"x":343.5543518066406,"y":402.0409851074219},{"x":369.553955078125,"y":401.45172119140625},{"x":395.0102233886719,"y":400.93212890625},{"x":61.62213897705078,"y":435.99761962890625},{"x":86.87250518798828,"y":435.1965637207031},{"x":112.13672637939453,"y":434.745361328125},{"x":137.52137756347656,"y":433.9971008300781},{"x":163.1786651611328,"y":433.056640625},{"x":188.8694305419922,"y":432.36090087890625},{"x":214.37022399902344,"y":431.7193908691406},{"x":240.08790588378906,"y":431.056640625},{"x":266.09063720703125,"y":430.1170349121094},{"x":291.8694152832031,"y":429.36572265625},{"x":317.71380615234375,"y":429.0467529296875},{"x":343.64556884765625,"y":428.33111572265625},{"x":58.32799530029297,"y":462.11798095703125},{"x":83.80270385742188,"y":461.7701110839844},{"x":109.56546783447266,"y":460.8628845214844},{"x":135.16571044921875,"y":459.9422607421875},{"x":160.92996215820312,"y":459.5142517089844},{"x":186.9582977294922,"y":458.8560791015625},{"x":212.86505126953125,"y":458.1878967285156},{"x":239.02467346191406,"y":457.3975524902344},{"x":264.9911193847656,"y":456.6817626953125},{"x":291.134765625,"y":456.0179138183594},{"x":317.3980712890625,"y":455.5384826660156},{"x":343.2984313964844,"y":454.89215087890625},{"x":55.18604278564453,"y":489.1313781738281},{"x":80.78169250488281,"y":488.4808654785156},{"x":106.92877960205078,"y":487.8422546386719},{"x":132.86038208007812,"y":487.13226318359375},{"x":158.8803253173828,"y":486.51336669921875},{"x":184.99331665039062,"y":485.9416809082031},{"x":211.26950073242188,"y":485.0433349609375},{"x":237.75099182128906,"y":484.49822998046875},{"x":263.9776611328125,"y":483.810546875},{"x":290.4804992675781,"y":483.14837646484375},{"x":316.9486999511719,"y":482.6795349121094},{"x":343.45391845703125,"y":481.957275390625},{"x":370.04150390625,"y":481.41192626953125},{"x":396.7244873046875,"y":480.865966796875},{"x":52.146060943603516,"y":516.5923461914062},{"x":77.94985961914062,"y":515.9326782226562},{"x":104.05316925048828,"y":515.3629150390625},{"x":130.3014373779297,"y":514.827880859375},{"x":156.76797485351562,"y":514.1461181640625},{"x":183.30992126464844,"y":513.720947265625},{"x":209.62261962890625,"y":512.8873291015625},{"x":289.7137451171875,"y":510.92279052734375},{"x":316.4695129394531,"y":510.40313720703125},{"x":343.2463073730469,"y":509.8974304199219},{"x":370.1502685546875,"y":509.3440856933594},{"x":397.01605224609375,"y":508.2925720214844},{"x":48.59197998046875,"y":544.2763061523438},{"x":74.88613891601562,"y":543.9943237304688},{"x":101.36194610595703,"y":543.6455688476562},{"x":127.80889129638672,"y":542.9842529296875},{"x":154.22024536132812,"y":542.1004638671875},{"x":181.30380249023438,"y":541.7349853515625},{"x":207.8387451171875,"y":541.0391235351562},{"x":286.9744873046875,"y":540.5418090820312},{"x":315.93475341796875,"y":538.8955688476562},{"x":343.1962585449219,"y":538.2852783203125},{"x":370.4057312011719,"y":537.8267822265625},{"x":397.82415771484375,"y":537.3013305664062},{"x":125.20664978027344,"y":571.965087890625},{"x":152.16445922851562,"y":571.3895263671875},{"x":178.96429443359375,"y":570.7867431640625},{"x":206.10009765625,"y":570.3321533203125},{"x":233.58599853515625,"y":569.839599609375},{"x":260.9615173339844,"y":569.0635986328125},{"x":288.21112060546875,"y":568.7091064453125},{"x":315.7311096191406,"y":568.1209106445312},{"x":343.1197204589844,"y":567.70751953125},{"x":370.73150634765625,"y":566.9613647460938},{"x":398.2362976074219,"y":566.7456665039062}],"reprojectionErrors":[{"x":0.273040771484375,"y":-0.030548095703125},{"x":0.26567840576171875,"y":0.09417724609375},{"x":0.1749725341796875,"y":0.117706298828125},{"x":-0.133636474609375,"y":0.088287353515625},{"x":-0.18695068359375,"y":-0.163116455078125},{"x":-0.2924346923828125,"y":-0.1287841796875},{"x":-0.2620849609375,"y":0.060150146484375},{"x":-0.5683441162109375,"y":0.158233642578125},{"x":-0.346527099609375,"y":0.159149169921875},{"x":-0.194427490234375,"y":-0.036590576171875},{"x":-0.2288818359375,"y":-0.05633544921875},{"x":-0.06591796875,"y":0.199005126953125},{"x":-0.24481201171875,"y":0.063446044921875},{"x":0.193389892578125,"y":-0.14007568359375},{"x":0.12306976318359375,"y":-0.052337646484375},{"x":0.0283966064453125,"y":0.04547119140625},{"x":0.0161590576171875,"y":-0.206268310546875},{"x":-0.0219879150390625,"y":-0.1605224609375},{"x":-0.240020751953125,"y":0.077850341796875},{"x":-0.400604248046875,"y":0.072021484375},{"x":-0.282135009765625,"y":0.0125732421875},{"x":-0.2933502197265625,"y":-0.024993896484375},{"x":-0.5042724609375,"y":0.21502685546875},{"x":-0.407867431640625,"y":0.26751708984375},{"x":-0.295654296875,"y":-0.111480712890625},{"x":-0.19134521484375,"y":-0.092864990234375},{"x":-0.06404876708984375,"y":-0.03472900390625},{"x":-0.035125732421875,"y":0.219818115234375},{"x":-0.075408935546875,"y":-0.0184326171875},{"x":-0.2868194580078125,"y":-0.02667236328125},{"x":-0.285552978515625,"y":-0.024993896484375},{"x":-0.4479827880859375,"y":0.09881591796875},{"x":-0.329986572265625,"y":0.148101806640625},{"x":-0.303955078125,"y":0.145538330078125},{"x":-0.31427001953125,"y":-0.041290283203125},{"x":0.11962890625,"y":-0.061004638671875},{"x":0.0599517822265625,"y":-0.1607666015625},{"x":0.18337249755859375,"y":-0.13604736328125},{"x":-0.1615142822265625,"y":-0.05169677734375},{"x":-0.1639404296875,"y":-0.1094970703125},{"x":-0.2364044189453125,"y":0.158599853515625},{"x":-0.4229736328125,"y":0.07269287109375},{"x":-0.265472412109375,"y":0.128662109375},{"x":-0.29693603515625,"y":0.15850830078125},{"x":-0.208587646484375,"y":-0.00555419921875},{"x":-0.0740966796875,"y":0.08331298828125},{"x":0.059051513671875,"y":-0.005218505859375},{"x":0.175689697265625,"y":-0.09356689453125},{"x":-0.2701530456542969,"y":-0.191650390625},{"x":-0.063079833984375,"y":-0.1160888671875},{"x":-0.052581787109375,"y":-0.132080078125},{"x":-0.085968017578125,"y":-0.18450927734375},{"x":-0.238433837890625,"y":-0.091796875},{"x":-0.3690643310546875,"y":-0.25726318359375},{"x":-0.1751251220703125,"y":-0.015869140625},{"x":-0.194610595703125,"y":0.16351318359375},{"x":-0.082763671875,"y":0.08538818359375},{"x":0.0931396484375,"y":-0.00799560546875},{"x":0.224822998046875,"y":-0.054962158203125},{"x":-0.15485382080078125,"y":-0.06201171875},{"x":-0.21561431884765625,"y":-0.2559814453125},{"x":-0.14409637451171875,"y":-0.1397705078125},{"x":0.0644989013671875,"y":0.19659423828125},{"x":-0.299591064453125,"y":0.01226806640625},{"x":-0.0175323486328125,"y":0.156005859375},{"x":1.862396240234375,"y":-1.0162353515625},{"x":0.088592529296875,"y":0.06915283203125},{"x":0.10064697265625,"y":0.11651611328125},{"x":0.249603271484375,"y":0.01007080078125},{"x":0.27227783203125,"y":-0.03143310546875},{"x":-0.15771484375,"y":-0.24700927734375},{"x":-0.2003936767578125,"y":-0.1549072265625},{"x":-0.247406005859375,"y":0.1051025390625},{"x":-0.074951171875,"y":-0.05938720703125},{"x":-0.081573486328125,"y":0.00689697265625}],"optimisedCameraToObject":{"translation":{"x":-0.1937856852694148,"y":0.0554463891274279,"z":0.40235808948816},"rotation":{"quaternion":{"W":0.9883675174103721,"X":-0.14978037381242942,"Y":0.02257901139232066,"Z":-0.013626385918951201}}},"cornersUsed":[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,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,false,false,true,true,true,true,true,true,true,true,true,true,true,true,false,false,false,true,true,true,true,false,false,false,true,true,true,true,true,true,true,true,true,true,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],"snapshotName":"img6.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img6.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4}],"locationInImageSpace":[{"x":418.7832946777344,"y":305.021728515625},{"x":444.7485656738281,"y":305.13385009765625},{"x":471.0685119628906,"y":305.6015319824219},{"x":497.0210876464844,"y":305.87982177734375},{"x":522.9235229492188,"y":306.0989990234375},{"x":549.2265014648438,"y":306.3437805175781},{"x":574.945556640625,"y":306.5688781738281},{"x":601.2911376953125,"y":306.6739196777344},{"x":627.2327270507812,"y":307.1195983886719},{"x":705.576416015625,"y":307.974609375},{"x":731.224609375,"y":308.11260986328125},{"x":757.1554565429688,"y":308.507568359375},{"x":419.0282287597656,"y":330.07501220703125},{"x":445.3875427246094,"y":330.18206787109375},{"x":471.7922668457031,"y":330.56024169921875},{"x":498.17901611328125,"y":330.7598876953125},{"x":524.803955078125,"y":330.8521423339844},{"x":550.9317016601562,"y":331.0393981933594},{"x":577.36474609375,"y":331.31268310546875},{"x":603.9378662109375,"y":331.65863037109375},{"x":630.079833984375,"y":331.9724426269531},{"x":709.2363891601562,"y":333.01214599609375},{"x":735.5422973632812,"y":333.1140441894531},{"x":761.900634765625,"y":333.4851989746094},{"x":419.1685485839844,"y":355.5865173339844},{"x":445.9537658691406,"y":355.7904357910156},{"x":472.83795166015625,"y":355.8640441894531},{"x":499.6334228515625,"y":356.0288391113281},{"x":526.1771240234375,"y":356.1341247558594},{"x":553.0853271484375,"y":356.5599060058594},{"x":579.8238525390625,"y":356.9859313964844},{"x":606.5447387695312,"y":357.0350341796875},{"x":633.2658081054688,"y":357.71356201171875},{"x":660.1810913085938,"y":357.7844543457031},{"x":686.78955078125,"y":358.1039733886719},{"x":713.1497802734375,"y":358.1851806640625},{"x":740.0371704101562,"y":358.6770935058594},{"x":766.102294921875,"y":358.7359313964844},{"x":419.5916442871094,"y":381.86090087890625},{"x":446.5783386230469,"y":381.9818420410156},{"x":473.850830078125,"y":382.14581298828125},{"x":500.87908935546875,"y":382.3207092285156},{"x":527.9969482421875,"y":382.7089538574219},{"x":555.20556640625,"y":382.7872009277344},{"x":582.0938110351562,"y":382.98553466796875},{"x":609.4242553710938,"y":383.2715148925781},{"x":636.271728515625,"y":383.488037109375},{"x":663.6483154296875,"y":383.96893310546875},{"x":690.3837280273438,"y":383.9517517089844},{"x":717.623291015625,"y":384.7396545410156},{"x":744.5982666015625,"y":384.5875244140625},{"x":771.44189453125,"y":385.01959228515625},{"x":419.9016418457031,"y":408.5993957519531},{"x":447.2563781738281,"y":408.83428955078125},{"x":474.89630126953125,"y":409.02716064453125},{"x":502.3778991699219,"y":409.2546691894531},{"x":529.8823852539062,"y":409.3841247558594},{"x":557.3173217773438,"y":409.72698974609375},{"x":584.733642578125,"y":410.08111572265625},{"x":612.2471923828125,"y":410.1596984863281},{"x":639.7279052734375,"y":410.6861877441406},{"x":667.0863647460938,"y":410.7264709472656},{"x":694.61181640625,"y":411.1266784667969},{"x":721.673583984375,"y":411.1301574707031},{"x":749.371337890625,"y":411.5140075683594},{"x":420.1180725097656,"y":436.19769287109375},{"x":448.104248046875,"y":436.36944580078125},{"x":475.9171447753906,"y":436.5350646972656},{"x":503.8974914550781,"y":436.88916015625},{"x":531.6263427734375,"y":437.0960998535156},{"x":559.6907958984375,"y":437.281005859375},{"x":587.1283569335938,"y":437.4057922363281},{"x":615.3418579101562,"y":437.9522705078125},{"x":643.30029296875,"y":438.13873291015625},{"x":671.06884765625,"y":438.46923828125},{"x":698.4663696289062,"y":438.3481750488281},{"x":726.2919311523438,"y":438.9024353027344},{"x":753.9717407226562,"y":438.948974609375},{"x":420.8374938964844,"y":465.0118103027344},{"x":448.8613586425781,"y":464.9944152832031},{"x":477.16766357421875,"y":465.0750732421875},{"x":505.4380798339844,"y":465.4088439941406},{"x":533.4766845703125,"y":465.6787414550781},{"x":562.0114135742188,"y":465.71820068359375},{"x":590.1395874023438,"y":466.05712890625},{"x":618.4306030273438,"y":466.3202819824219},{"x":646.83740234375,"y":466.734130859375},{"x":674.7733764648438,"y":466.89105224609375},{"x":702.9131469726562,"y":467.193603515625},{"x":730.774658203125,"y":467.2129211425781},{"x":759.0662231445312,"y":467.6844482421875},{"x":420.98199462890625,"y":494.16143798828125},{"x":449.4372863769531,"y":494.29150390625},{"x":478.2538757324219,"y":494.3757629394531},{"x":507.0686340332031,"y":494.8887023925781},{"x":535.378173828125,"y":494.86907958984375},{"x":564.4194946289062,"y":495.23150634765625},{"x":593.029296875,"y":495.2974853515625},{"x":621.72802734375,"y":495.6587219238281},{"x":650.1598510742188,"y":495.8545227050781},{"x":678.8237915039062,"y":496.1080017089844},{"x":707.2218627929688,"y":496.154052734375},{"x":735.702392578125,"y":496.5070495605469},{"x":763.7176513671875,"y":496.49163818359375},{"x":421.3426513671875,"y":524.5377197265625},{"x":450.3255615234375,"y":524.473876953125},{"x":479.68316650390625,"y":524.8040161132812},{"x":508.6680908203125,"y":524.9321899414062},{"x":537.6615600585938,"y":525.0615844726562},{"x":566.8128051757812,"y":525.2706909179688},{"x":595.8997192382812,"y":525.6194458007812},{"x":625.1067504882812,"y":525.7966918945312},{"x":653.8942260742188,"y":525.9230346679688},{"x":682.8148193359375,"y":526.107177734375},{"x":711.8079833984375,"y":526.4354858398438},{"x":740.31640625,"y":526.3229370117188},{"x":769.1373901367188,"y":526.5269165039062},{"x":421.7765197753906,"y":555.8267211914062},{"x":451.26470947265625,"y":555.9683227539062},{"x":480.8648986816406,"y":555.8794555664062},{"x":510.36663818359375,"y":556.1329956054688},{"x":539.9653930664062,"y":556.1056518554688},{"x":569.5609130859375,"y":556.3984985351562},{"x":598.7674560546875,"y":556.4627075195312},{"x":628.3190307617188,"y":556.83349609375},{"x":657.4617919921875,"y":556.6890869140625},{"x":686.9697875976562,"y":557.076904296875},{"x":716.1284790039062,"y":557.06201171875},{"x":745.1485595703125,"y":557.134765625}],"reprojectionErrors":[{"x":-0.148101806640625,"y":-0.035369873046875},{"x":0.125335693359375,"y":0.090118408203125},{"x":0.014862060546875,"y":-0.132537841796875},{"x":0.240264892578125,"y":-0.15838623046875},{"x":0.4820556640625,"y":-0.1177978515625},{"x":0.2872314453125,"y":-0.095489501953125},{"x":0.6380615234375,"y":-0.04620361328125},{"x":0.32177734375,"y":0.130340576171875},{"x":0.36676025390625,"y":-0.026519775390625},{"x":-0.34130859375,"y":0.136138916015625},{"x":-0.160919189453125,"y":-0.184173583984375},{"x":0.0655517578125,"y":-0.063201904296875},{"x":0.216583251953125,"y":-0.206573486328125},{"x":0.353302001953125,"y":-0.1646728515625},{"x":0.21710205078125,"y":-0.0086669921875},{"x":0.54119873046875,"y":0.059051513671875},{"x":0.5206298828125,"y":0.04736328125},{"x":0.31842041015625,"y":-0.0303955078125},{"x":0.50341796875,"y":-0.069427490234375},{"x":0.0419921875,"y":-0.245758056640625},{"x":-0.13494873046875,"y":-0.0469970703125},{"x":0.095001220703125,"y":-0.11199951171875},{"x":0.122528076171875,"y":0.038330078125},{"x":0.205596923828125,"y":0.103546142578125},{"x":0.50482177734375,"y":0.23431396484375},{"x":0.401611328125,"y":0.05059814453125},{"x":0.42767333984375,"y":-0.12738037109375},{"x":0.4287109375,"y":0.0775146484375},{"x":0.38446044921875,"y":-0.34112548828125},{"x":0.09869384765625,"y":-0.146270751953125},{"x":0.07000732421875,"y":-0.194183349609375},{"x":0.237548828125,"y":0.001983642578125},{"x":-0.17633056640625,"y":-0.206787109375},{"x":0.175537109375,"y":0.023223876953125},{"x":-0.2393798828125,"y":-0.136993408203125},{"x":0.083282470703125,"y":-0.0509033203125},{"x":0.088531494140625,"y":-0.002471923828125},{"x":0.30389404296875,"y":0.040374755859375},{"x":0.39312744140625,"y":-0.124755859375},{"x":0.35260009765625,"y":0.025390625},{"x":0.59100341796875,"y":0.060699462890625},{"x":0.34332275390625,"y":0.01361083984375},{"x":0.5323486328125,"y":0.04119873046875},{"x":0.14361572265625,"y":-0.1904296875},{"x":0.344970703125,"y":0.081146240234375},{"x":-0.01116943359375,"y":-0.447265625},{"x":-0.158447265625,"y":-0.03057861328125},{"x":-0.232421875,"y":-0.193084716796875},{"x":-0.29595947265625,"y":0.111297607421875},{"x":0.036041259765625,"y":0.071929931640625},{"x":0.05035400390625,"y":0.079193115234375},{"x":0.187957763671875,"y":0.056427001953125},{"x":0.26513671875,"y":0.13629150390625},{"x":0.37176513671875,"y":0.007293701171875},{"x":0.45440673828125,"y":-0.128448486328125},{"x":0.394775390625,"y":0.015838623046875},{"x":0.3204345703125,"y":-0.2833251953125},{"x":0.318359375,"y":-0.09185791015625},{"x":0.09686279296875,"y":-0.255889892578125},{"x":0.2841796875,"y":-0.01885986328125},{"x":-0.22174072265625,"y":-0.157867431640625},{"x":-0.251251220703125,"y":0.2548828125},{"x":-0.162322998046875,"y":0.26641845703125},{"x":0.06646728515625,"y":0.28790283203125},{"x":0.091796875,"y":0.12469482421875},{"x":0.19146728515625,"y":0.1259765625},{"x":0.635986328125,"y":0.203369140625},{"x":0.25823974609375,"y":-0.13726806640625},{"x":0.08673095703125,"y":-0.114166259765625},{"x":0.0537109375,"y":-0.23150634765625},{"x":0.33782958984375,"y":0.106353759765625},{"x":0.13751220703125,"y":-0.2275390625},{"x":0.02410888671875,"y":-0.050140380859375},{"x":-0.70147705078125,"y":-0.02874755859375},{"x":-0.250396728515625,"y":0.158905029296875},{"x":-0.116119384765625,"y":0.251495361328125},{"x":0.01702880859375,"y":0.093902587890625},{"x":0.34228515625,"y":0.003143310546875},{"x":0.27728271484375,"y":-0.008270263671875},{"x":0.21514892578125,"y":-0.0836181640625},{"x":-0.0130615234375,"y":-0.30682373046875},{"x":0.17669677734375,"y":-0.270294189453125},{"x":0.10723876953125,"y":-0.376617431640625},{"x":0.25811767578125,"y":-0.196929931640625},{"x":-0.08160400390625,"y":-0.466705322265625},{"x":-0.568328857421875,"y":0.176177978515625},{"x":-0.136871337890625,"y":0.202545166015625},{"x":-0.102020263671875,"y":0.27679443359375},{"x":-0.10345458984375,"y":-0.075592041015625},{"x":0.3594970703125,"y":0.10662841796875},{"x":0.04705810546875,"y":-0.0911865234375},{"x":0.0546875,"y":-0.18316650390625},{"x":0.2047119140625,"y":-0.20843505859375},{"x":0.06829833984375,"y":-0.289398193359375},{"x":0.1407470703125,"y":-0.161041259765625},{"x":0.07110595703125,"y":-0.337738037109375},{"x":0.404541015625,"y":-0.1441650390625},{"x":-0.642547607421875,"y":0.0162353515625},{"x":-0.3143310546875,"y":0.2218017578125},{"x":-0.397186279296875,"y":0.03448486328125},{"x":-0.146575927734375,"y":0.05023193359375},{"x":0.053466796875,"y":0.06585693359375},{"x":0.05084228515625,"y":0.0028076171875},{"x":0.06494140625,"y":-0.19879150390625},{"x":0.1182861328125,"y":-0.2049560546875},{"x":0.13909912109375,"y":-0.2388916015625},{"x":0.02862548828125,"y":-0.41595458984375},{"x":0.34161376953125,"y":-0.1512451171875},{"x":0.27789306640625,"y":-0.20208740234375},{"x":-0.78076171875,"y":-0.15460205078125},{"x":-0.520355224609375,"y":-0.17022705078125},{"x":-0.40936279296875,"y":0.04473876953125},{"x":-0.240325927734375,"y":-0.08258056640625},{"x":-0.21160888671875,"y":0.07110595703125},{"x":-0.225830078125,"y":-0.09539794921875},{"x":0.099853515625,"y":-0.03314208984375},{"x":0.028564453125,"y":-0.2774658203125},{"x":0.17120361328125,"y":-0.26776123046875},{"x":0.32000732421875,"y":-0.12628173828125},{"x":0.544189453125,"y":-0.072509765625}],"optimisedCameraToObject":{"translation":{"x":0.014465013208941923,"y":-0.006444200755691412,"z":0.3897197034946522},"rotation":{"quaternion":{"W":0.9848680958641197,"X":-0.1729867593220382,"Y":-0.00984421325130166,"Z":0.003675093700182074}}},"cornersUsed":[true,true,true,true,true,true,true,true,true,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,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,false,false],"snapshotName":"img7.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img7.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.13510259985923767,"z":-5.434296326711774E-5}],"locationInImageSpace":[{"x":94.55457305908203,"y":256.2789611816406},{"x":121.28324890136719,"y":257.55059814453125},{"x":148.47007751464844,"y":258.27191162109375},{"x":175.64390563964844,"y":258.9859619140625},{"x":202.3284149169922,"y":260.1810607910156},{"x":229.1345977783203,"y":261.1844482421875},{"x":255.48106384277344,"y":262.2179870605469},{"x":282.0087890625,"y":263.2172546386719},{"x":308.1299743652344,"y":264.18316650390625},{"x":334.07476806640625,"y":265.2356262207031},{"x":360.1573181152344,"y":266.29351806640625},{"x":385.794677734375,"y":267.1773376464844},{"x":411.8833923339844,"y":268.2302551269531},{"x":437.326171875,"y":269.2294616699219},{"x":89.32225799560547,"y":279.6879577636719},{"x":116.69408416748047,"y":280.0448913574219},{"x":144.2071990966797,"y":281.1212158203125},{"x":171.77362060546875,"y":282.2632141113281},{"x":198.98800659179688,"y":283.07440185546875},{"x":226.0372314453125,"y":284.3111877441406},{"x":252.97608947753906,"y":285.1484069824219},{"x":279.9427795410156,"y":286.00946044921875},{"x":359.3571472167969,"y":288.9468994140625},{"x":385.7203674316406,"y":290.0016784667969},{"x":411.91790771484375,"y":290.9934387207031},{"x":437.8488464355469,"y":291.92724609375},{"x":111.72427368164062,"y":303.8904724121094},{"x":139.5696258544922,"y":305.10772705078125},{"x":167.8024444580078,"y":306.0599060058594},{"x":195.37997436523438,"y":306.910888671875},{"x":223.0958709716797,"y":307.89141845703125},{"x":250.3024444580078,"y":308.9294738769531},{"x":277.8088684082031,"y":309.7304382324219},{"x":358.68505859375,"y":312.632080078125},{"x":385.2696838378906,"y":313.31402587890625},{"x":412.13360595703125,"y":314.16119384765625},{"x":438.5019836425781,"y":315.2860412597656},{"x":135.00726318359375,"y":330.01092529296875},{"x":163.2051239013672,"y":330.7365417480469},{"x":191.34799194335938,"y":331.3489990234375},{"x":219.78244018554688,"y":332.2564392089844},{"x":247.50804138183594,"y":333.27166748046875},{"x":275.4201965332031,"y":334.21405029296875},{"x":302.9147644042969,"y":334.9197998046875},{"x":330.552001953125,"y":336.0188903808594},{"x":357.85833740234375,"y":336.8662109375},{"x":385.135986328125,"y":337.6437683105469},{"x":412.2365417480469,"y":338.5637512207031},{"x":439.03826904296875,"y":339.4617614746094},{"x":129.76588439941406,"y":355.7846984863281},{"x":158.9116668701172,"y":356.09326171875},{"x":187.4792938232422,"y":356.99896240234375},{"x":216.3303680419922,"y":357.9400634765625},{"x":244.7996063232422,"y":358.6001281738281},{"x":273.0670471191406,"y":359.43695068359375},{"x":301.20050048828125,"y":360.2914733886719},{"x":329.18206787109375,"y":361.1908264160156},{"x":357.1425476074219,"y":361.9908447265625},{"x":384.8604431152344,"y":362.8330078125},{"x":412.4972839355469,"y":363.8602294921875},{"x":439.89031982421875,"y":364.5579833984375},{"x":65.20616149902344,"y":380.8540954589844},{"x":94.4286880493164,"y":381.22479248046875},{"x":124.4587631225586,"y":382.24444580078125},{"x":153.88014221191406,"y":382.9646911621094},{"x":183.59756469726562,"y":383.4424133300781},{"x":212.7489013671875,"y":384.0815124511719},{"x":241.82733154296875,"y":385.0612487792969},{"x":270.6280517578125,"y":385.8035888671875},{"x":299.26312255859375,"y":386.40423583984375},{"x":327.7384948730469,"y":387.11553955078125},{"x":356.0578308105469,"y":388.0409851074219},{"x":384.3243103027344,"y":388.9604187011719},{"x":412.4168395996094,"y":389.7309875488281},{"x":440.3861389160156,"y":390.416259765625},{"x":58.69386672973633,"y":408.1959533691406},{"x":88.80425262451172,"y":409.24334716796875},{"x":119.21121215820312,"y":409.9338684082031},{"x":149.37722778320312,"y":410.34429931640625},{"x":179.35594177246094,"y":411.0837097167969},{"x":208.99411010742188,"y":411.78094482421875},{"x":238.60118103027344,"y":412.57037353515625},{"x":268.1590576171875,"y":413.06787109375},{"x":297.35614013671875,"y":413.87261962890625},{"x":326.5254821777344,"y":414.5577087402344},{"x":355.1974182128906,"y":415.2539978027344},{"x":384.1537780761719,"y":416.1615295410156},{"x":412.85638427734375,"y":416.83099365234375},{"x":441.1854553222656,"y":417.5540771484375},{"x":51.29292297363281,"y":437.3069152832031},{"x":82.67132568359375,"y":438.03485107421875},{"x":113.36273193359375,"y":438.40777587890625},{"x":144.5183563232422,"y":438.90887451171875},{"x":174.70973205566406,"y":439.8441467285156},{"x":205.3339080810547,"y":440.30267333984375},{"x":235.58766174316406,"y":440.8707580566406},{"x":265.45098876953125,"y":441.5006408691406},{"x":295.08209228515625,"y":442.08612060546875},{"x":324.77294921875,"y":442.8124084472656},{"x":354.3326416015625,"y":443.3934326171875},{"x":383.81524658203125,"y":444.008056640625},{"x":412.9233703613281,"y":444.72802734375},{"x":442.0559387207031,"y":445.54815673828125},{"x":44.508724212646484,"y":467.7779541015625},{"x":75.99909973144531,"y":467.9524841308594},{"x":107.38640594482422,"y":468.5581359863281},{"x":138.80276489257812,"y":468.8460388183594},{"x":169.89462280273438,"y":469.42034912109375},{"x":201.24908447265625,"y":469.820068359375},{"x":232.04364013671875,"y":470.81842041015625},{"x":262.84222412109375,"y":471.07391357421875},{"x":293.1441650390625,"y":471.7955017089844},{"x":323.29034423828125,"y":472.26806640625},{"x":353.59039306640625,"y":472.8970947265625},{"x":383.2913818359375,"y":473.5843505859375},{"x":413.1617431640625,"y":474.26513671875},{"x":442.8878479003906,"y":474.87945556640625},{"x":37.15386962890625,"y":498.7793884277344},{"x":69.19014739990234,"y":499.1240234375},{"x":101.39224243164062,"y":499.78985595703125},{"x":133.4049530029297,"y":500.0848693847656},{"x":165.05177307128906,"y":500.5614318847656},{"x":196.8150634765625,"y":501.11328125},{"x":228.1849365234375,"y":501.36468505859375},{"x":259.6526794433594,"y":502.02398681640625},{"x":290.73980712890625,"y":502.296142578125},{"x":321.7164001464844,"y":502.96820068359375},{"x":352.2945861816406,"y":503.6560363769531},{"x":383.06024169921875,"y":504.2710876464844},{"x":413.3356018066406,"y":504.7394714355469},{"x":443.6953125,"y":505.3249206542969}],"reprojectionErrors":[{"x":0.13373565673828125,"y":0.129425048828125},{"x":0.40766143798828125,"y":-0.21185302734375},{"x":0.12213134765625,"y":0.00494384765625},{"x":-0.2533721923828125,"y":0.23663330078125},{"x":-0.2441558837890625,"y":-0.0052490234375},{"x":-0.4628448486328125,"y":-0.048065185546875},{"x":-0.3296051025390625,"y":-0.113800048828125},{"x":-0.486968994140625,"y":-0.138153076171875},{"x":-0.348663330078125,"y":-0.1221923828125},{"x":-0.146270751953125,"y":-0.185882568359375},{"x":-0.1954345703125,"y":-0.248321533203125},{"x":0.08538818359375,"y":-0.13006591796875},{"x":-0.201751708984375,"y":-0.1744384765625},{"x":0.039093017578125,"y":-0.15875244140625},{"x":-0.07717132568359375,"y":-0.244659423828125},{"x":0.04514312744140625,"y":0.29888916015625},{"x":-0.0787811279296875,"y":0.13037109375},{"x":-0.3626861572265625,"y":-0.09661865234375},{"x":-0.4029083251953125,"y":0.0142822265625},{"x":-0.3879852294921875,"y":-0.293426513671875},{"x":-0.37432861328125,"y":-0.194732666015625},{"x":-0.501708984375,"y":-0.1131591796875},{"x":-0.031951904296875,"y":-0.287567138671875},{"x":0.16558837890625,"y":-0.24102783203125},{"x":-0.11933135986328125,"y":0.287109375},{"x":-0.0691986083984375,"y":-0.055450439453125},{"x":-0.4220428466796875,"y":-0.089019775390625},{"x":-0.579376220703125,"y":-0.17486572265625},{"x":-0.343048095703125,"y":-0.31182861328125},{"x":-0.523895263671875,"y":-0.20538330078125},{"x":-0.14306640625,"y":-0.348175048828125},{"x":0.113006591796875,"y":-0.09869384765625},{"x":-0.035186767578125,"y":-0.00872802734375},{"x":-0.1996307373046875,"y":-0.166107177734375},{"x":-0.1524658203125,"y":0.072479248046875},{"x":-0.5151214599609375,"y":0.022186279296875},{"x":-0.2888946533203125,"y":-0.129913330078125},{"x":-0.2137451171875,"y":-0.2530517578125},{"x":-0.06451416015625,"y":-0.2144775390625},{"x":-0.014617919921875,"y":-0.10076904296875},{"x":0.0828857421875,"y":-0.124176025390625},{"x":0.348297119140625,"y":-0.120452880859375},{"x":-0.051849365234375,"y":-0.462860107421875},{"x":-0.3491058349609375,"y":0.03338623046875},{"x":-0.189117431640625,"y":-0.061767578125},{"x":-0.435302734375,"y":-0.18670654296875},{"x":-0.4241485595703125,"y":-0.02508544921875},{"x":-0.33740234375,"y":-0.03485107421875},{"x":-0.24456787109375,"y":-0.0570068359375},{"x":-0.009429931640625,"y":-0.07086181640625},{"x":0.05224609375,"y":-0.245697021484375},{"x":0.22198486328125,"y":-0.0863037109375},{"x":0.13535308837890625,"y":-0.46514892578125},{"x":0.5703964233398438,"y":-0.085479736328125},{"x":0.07613372802734375,"y":-0.349365234375},{"x":0.0668487548828125,"y":-0.308502197265625},{"x":-0.36407470703125,"y":-0.0198974609375},{"x":-0.3563690185546875,"y":0.112457275390625},{"x":-0.4050445556640625,"y":-0.0908203125},{"x":-0.30706787109375,"y":-0.05181884765625},{"x":-0.176239013671875,"y":0.1336669921875},{"x":-0.02020263671875,"y":0.21319580078125},{"x":0.155731201171875,"y":0.083160400390625},{"x":0.24676513671875,"y":-0.036407470703125},{"x":0.37237548828125,"y":-0.002716064453125},{"x":0.480377197265625,"y":0.12054443359375},{"x":0.0750579833984375,"y":-0.1043701171875},{"x":0.218475341796875,"y":-0.44805908203125},{"x":-0.0612945556640625,"y":-0.42999267578125},{"x":-0.2287445068359375,"y":-0.127044677734375},{"x":-0.339447021484375,"y":-0.1484375},{"x":-0.242095947265625,"y":-0.123077392578125},{"x":-0.248016357421875,"y":-0.1854248046875},{"x":-0.340911865234375,"y":0.04852294921875},{"x":-0.211029052734375,"y":-0.020538330078125},{"x":-0.193084716796875,"y":0.034271240234375},{"x":0.180816650390625,"y":0.081939697265625},{"x":0.127227783203125,"y":-0.077667236328125},{"x":0.18267822265625,"y":0.00469970703125},{"x":0.46539306640625,"y":0.037200927734375},{"x":0.6354560852050781,"y":-0.40521240234375},{"x":0.13201141357421875,"y":-0.48040771484375},{"x":0.18379974365234375,"y":-0.19635009765625},{"x":-0.362457275390625,"y":-0.0362548828125},{"x":-0.080322265625,"y":-0.3062744140625},{"x":-0.3687896728515625,"y":-0.095550537109375},{"x":-0.426605224609375,"y":0.009521484375},{"x":-0.235595703125,"y":0.056610107421875},{"x":0.04412841796875,"y":0.151824951171875},{"x":0.11883544921875,"y":0.109832763671875},{"x":0.177703857421875,"y":0.216644287109375},{"x":0.164947509765625,"y":0.293304443359375},{"x":0.376251220703125,"y":0.267974853515625},{"x":0.411163330078125,"y":0.145721435546875},{"x":0.2943878173828125,"y":-0.88922119140625},{"x":0.32663726806640625,"y":-0.466796875},{"x":0.3247222900390625,"y":-0.47186279296875},{"x":0.1543731689453125,"y":-0.1556396484375},{"x":0.167083740234375,"y":-0.12237548828125},{"x":-0.226287841796875,"y":0.0888671875},{"x":-0.2052459716796875,"y":-0.295196533203125},{"x":-0.335662841796875,"y":0.0667724609375},{"x":-0.11871337890625,"y":-0.034210205078125},{"x":0.102813720703125,"y":0.11688232421875},{"x":0.01751708984375,"y":0.11444091796875},{"x":0.3765869140625,"y":0.056671142578125},{"x":0.409881591796875,"y":0.0081787109375},{"x":0.429351806640625,"y":0.028839111328125},{"x":0.221038818359375,"y":-0.651458740234375},{"x":0.38330841064453125,"y":-0.460174560546875},{"x":0.2366943359375,"y":-0.587158203125},{"x":0.1342010498046875,"y":-0.3404541015625},{"x":0.2501678466796875,"y":-0.272491455078125},{"x":0.10015869140625,"y":-0.277099609375},{"x":0.191986083984375,"y":0.021392822265625},{"x":0.032379150390625,"y":-0.08544921875},{"x":0.097869873046875,"y":0.1973876953125},{"x":0.116455078125,"y":0.08270263671875},{"x":0.37420654296875,"y":-0.04534912109375},{"x":0.283416748046875,"y":-0.098388671875},{"x":0.520111083984375,"y":-0.00250244140625},{"x":0.5079345703125,"y":-0.021575927734375}],"optimisedCameraToObject":{"translation":{"x":-0.16910419432839088,"y":-0.03387471732619506,"z":0.3861581509024149},"rotation":{"quaternion":{"W":0.9721034737942273,"X":-0.2322952136052984,"Y":-0.031010696475127168,"Z":0.0095972223790156}}},"cornersUsed":[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,true,false,true,true,true,true,true,true,true,false,false,true,true,true,true,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,true,true,true,true],"snapshotName":"img8.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img8.png"},{"locationInObjectSpace":[{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4}],"locationInImageSpace":[{"x":527.1996459960938,"y":50.936492919921875},{"x":553.097900390625,"y":51.228397369384766},{"x":579.9658813476562,"y":51.301170349121094},{"x":606.0328979492188,"y":52.05740737915039},{"x":632.7400512695312,"y":52.271202087402344},{"x":712.6797485351562,"y":53.534698486328125},{"x":397.02740478515625,"y":69.96752166748047},{"x":422.89031982421875,"y":70.09918975830078},{"x":448.8349609375,"y":70.48184967041016},{"x":527.8184204101562,"y":71.77948760986328},{"x":553.9794311523438,"y":72.00208282470703},{"x":580.7310180664062,"y":72.21044921875},{"x":607.5972900390625,"y":72.65709686279297},{"x":634.3947143554688,"y":72.8812484741211},{"x":661.6824951171875,"y":73.2448959350586},{"x":688.7073974609375,"y":74.07942199707031},{"x":716.103515625,"y":74.37330627441406},{"x":395.4848327636719,"y":90.61410522460938},{"x":421.7385559082031,"y":91.07337951660156},{"x":448.0794677734375,"y":91.51899719238281},{"x":474.598388671875,"y":91.8587417602539},{"x":501.1141662597656,"y":92.14615631103516},{"x":528.1174926757812,"y":92.60751342773438},{"x":554.9146118164062,"y":93.15227508544922},{"x":636.6718139648438,"y":94.37478637695312},{"x":664.0496826171875,"y":94.88980102539062},{"x":691.6712036132812,"y":95.1624526977539},{"x":719.9263305664062,"y":96.23623657226562},{"x":747.09228515625,"y":96.25357818603516},{"x":394.1541748046875,"y":112.08263397216797},{"x":420.8685607910156,"y":112.69877624511719},{"x":501.10369873046875,"y":113.86973571777344},{"x":528.2018432617188,"y":114.30461120605469},{"x":555.850830078125,"y":114.72969055175781},{"x":666.3547973632812,"y":116.78755187988281},{"x":694.2766723632812,"y":117.24312591552734},{"x":392.6357421875,"y":134.00033569335938},{"x":419.3896484375,"y":134.55859375},{"x":501.2081298828125,"y":136.15158081054688},{"x":528.863037109375,"y":136.8613739013672},{"x":556.5271606445312,"y":137.29888916015625},{"x":584.6072387695312,"y":137.72970581054688},{"x":669.11181640625,"y":139.30186462402344},{"x":390.9899597167969,"y":156.86004638671875},{"x":418.4845886230469,"y":157.3591766357422},{"x":445.8529052734375,"y":157.91018676757812},{"x":473.5207214355469,"y":158.37124633789062},{"x":501.3175048828125,"y":158.94300842285156},{"x":529.3547973632812,"y":159.79954528808594},{"x":557.3307495117188,"y":160.14352416992188},{"x":585.790283203125,"y":160.90528869628906},{"x":614.0924072265625,"y":161.2730712890625},{"x":642.981689453125,"y":162.13450622558594},{"x":671.5797119140625,"y":162.67417907714844},{"x":389.419189453125,"y":180.0198974609375},{"x":417.0794677734375,"y":180.95925903320312},{"x":445.0727233886719,"y":181.39300537109375},{"x":473.2317810058594,"y":182.0398406982422},{"x":501.32659912109375,"y":182.47657775878906},{"x":529.7908325195312,"y":183.2082061767578},{"x":558.5232543945312,"y":184.04310607910156},{"x":587.1710205078125,"y":184.7506103515625},{"x":616.0323486328125,"y":185.3022918701172},{"x":645.0884399414062,"y":186.02313232421875},{"x":674.5264282226562,"y":186.8373260498047},{"x":703.78076171875,"y":187.34324645996094},{"x":733.215087890625,"y":188.18617248535156},{"x":387.9185791015625,"y":204.01060485839844},{"x":416.0706787109375,"y":204.9849395751953},{"x":444.2393493652344,"y":205.5858612060547},{"x":472.9168395996094,"y":206.232177734375},{"x":501.39801025390625,"y":206.98570251464844},{"x":530.33056640625,"y":207.7052001953125},{"x":559.1461181640625,"y":208.49508666992188},{"x":588.725341796875,"y":209.15182495117188},{"x":617.8428344726562,"y":209.89425659179688},{"x":647.3657836914062,"y":210.6688995361328},{"x":737.2030029296875,"y":212.9920654296875},{"x":386.1068115234375,"y":228.84002685546875},{"x":414.94500732421875,"y":229.78269958496094},{"x":443.63592529296875,"y":230.52610778808594},{"x":472.4349365234375,"y":231.24520874023438},{"x":501.411865234375,"y":232.14776611328125},{"x":530.9393310546875,"y":233.02108764648438},{"x":560.1987915039062,"y":233.73007202148438},{"x":589.9944458007812,"y":234.3313446044922},{"x":619.9309692382812,"y":235.355224609375},{"x":649.9640502929688,"y":236.20584106445312},{"x":384.6103210449219,"y":254.37893676757812},{"x":413.31842041015625,"y":255.21145629882812},{"x":442.72119140625,"y":256.1203918457031},{"x":472.042236328125,"y":256.97174072265625},{"x":501.60260009765625,"y":258.020263671875},{"x":531.7156372070312,"y":258.9290466308594},{"x":561.3218994140625,"y":259.8035888671875},{"x":591.5203247070312,"y":260.6677551269531},{"x":621.9773559570312,"y":261.4845886230469},{"x":652.6124267578125,"y":262.519775390625},{"x":683.176025390625,"y":263.6356201171875}],"reprojectionErrors":[{"x":0.27618408203125,"y":-0.40946197509765625},{"x":0.0521240234375,"y":0.017730712890625},{"x":0.049652099609375,"y":0.126373291015625},{"x":0.10113525390625,"y":4.57763671875E-4},{"x":-0.0916748046875,"y":-0.4272613525390625},{"x":0.09637451171875,"y":-0.283294677734375},{"x":-0.04229736328125,"y":-0.1044769287109375},{"x":0.09228515625,"y":-0.529754638671875},{"x":-0.02227783203125,"y":-0.39696502685546875},{"x":0.13848876953125,"y":-0.15876007080078125},{"x":0.126922607421875,"y":-0.16650390625},{"x":0.255706787109375,"y":-0.10533905029296875},{"x":0.03289794921875,"y":-0.2014312744140625},{"x":0.15081787109375,"y":-0.36415863037109375},{"x":-0.06744384765625,"y":-0.33896636962890625},{"x":-0.00592041015625,"y":-0.4039154052734375},{"x":-0.0606689453125,"y":-0.2092742919921875},{"x":0.0277099609375,"y":-0.31378936767578125},{"x":-0.0369873046875,"y":0.02207183837890625},{"x":-0.142333984375,"y":-0.23273468017578125},{"x":0.3074951171875,"y":-0.2214202880859375},{"x":0.38604736328125,"y":-0.2291259765625},{"x":0.05242919921875,"y":-0.2103424072265625},{"x":0.16790771484375,"y":-0.32401275634765625},{"x":0.18023681640625,"y":-0.04132080078125},{"x":0.24664306640625,"y":-0.255157470703125},{"x":0.177001953125,"y":-0.4722900390625},{"x":0.030517578125,"y":-0.3054046630859375},{"x":-0.0313720703125,"y":-0.1987152099609375},{"x":-0.015228271484375,"y":-0.1288299560546875},{"x":0.12213134765625,"y":-0.1013641357421875},{"x":0.183258056640625,"y":-0.1276397705078125},{"x":0.152587890625,"y":-0.4222412109375},{"x":0.01080322265625,"y":-0.343414306640625},{"x":0.14117431640625,"y":-0.237762451171875},{"x":0.055023193359375,"y":-0.1773681640625},{"x":0.029327392578125,"y":-0.221527099609375},{"x":0.06103515625,"y":-0.31878662109375},{"x":0.15728759765625,"y":-0.3580322265625},{"x":0.18896484375,"y":-0.224884033203125},{"x":0.17327880859375,"y":-0.2442474365234375},{"x":0.0361328125,"y":-0.2023162841796875},{"x":-0.048736572265625,"y":-0.132659912109375},{"x":0.202362060546875,"y":-0.1894073486328125},{"x":0.160400390625,"y":-0.1958465576171875},{"x":0.39227294921875,"y":-0.256317138671875},{"x":0.01580810546875,"y":-0.1672515869140625},{"x":0.2548828125,"y":-0.1473846435546875},{"x":0.24072265625,"y":-0.1432037353515625},{"x":-0.17333984375,"y":-0.0301361083984375},{"x":-0.2220458984375,"y":0.0682525634765625},{"x":-0.367889404296875,"y":-0.143310546875},{"x":-0.198883056640625,"y":-0.139617919921875},{"x":0.32635498046875,"y":-0.1938629150390625},{"x":0.20758056640625,"y":0.0329132080078125},{"x":0.1068115234375,"y":-0.1465301513671875},{"x":0.0667724609375,"y":-0.1363067626953125},{"x":-0.532501220703125,"y":0.123870849609375},{"x":-0.09051513671875,"y":0.1102142333984375},{"x":-0.170135498046875,"y":0.03607177734375},{"x":0.003631591796875,"y":0.035552978515625},{"x":0.1083984375,"y":-0.1461181640625},{"x":-0.170654296875,"y":-0.17193603515625},{"x":0.224365234375,"y":-0.1473388671875},{"x":0.19305419921875,"y":-0.09619140625},{"x":0.06732177734375,"y":0.018585205078125},{"x":0.0172119140625,"y":-0.2203369140625}],"optimisedCameraToObject":{"translation":{"x":0.0030462427396581756,"y":-0.15677285595546592,"z":0.4014745691435667},"rotation":{"quaternion":{"W":0.9807377160945954,"X":-0.19181258213494481,"Y":0.028058494202384227,"Z":0.023962188284392}}},"cornersUsed":[false,false,false,false,false,true,true,true,true,true,false,false,true,false,true,true,true,false,false,true,true,true,true,true,true,true,true,false,true,true,true,true,true,true,true,false,false,true,true,true,false,true,true,true,false,false,true,true,true,false,false,false,true,true,false,false,true,true,false,false,true,true,true,true,false,false,true,false,false,false,true,true,true,true,true,true,true,true,true,true,true,false,false,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,false,false,true,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,false,false,false],"snapshotName":"img9.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img9.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.060045599937438965,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.10507979989051819,"y":0.0750569999217987,"z":-2.3033602337818593E-4},{"x":0.12009119987487793,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.13510259985923767,"z":-1.2209254782646894E-4}],"locationInImageSpace":[{"x":419.4114990234375,"y":60.772064208984375},{"x":531.408203125,"y":60.769004821777344},{"x":559.7528686523438,"y":60.17254638671875},{"x":644.3901977539062,"y":60.635406494140625},{"x":673.1636352539062,"y":60.537925720214844},{"x":701.2493896484375,"y":60.37974548339844},{"x":729.843017578125,"y":60.484901428222656},{"x":758.396240234375,"y":60.34413146972656},{"x":419.2344055175781,"y":89.18222045898438},{"x":502.99627685546875,"y":89.04784393310547},{"x":530.9685668945312,"y":89.01189422607422},{"x":559.137451171875,"y":89.05239868164062},{"x":587.45751953125,"y":88.92782592773438},{"x":615.281005859375,"y":89.17496490478516},{"x":643.7778930664062,"y":88.71778869628906},{"x":672.4114990234375,"y":88.78483581542969},{"x":700.557373046875,"y":88.85700225830078},{"x":729.1069946289062,"y":88.92366027832031},{"x":757.6171264648438,"y":89.21440124511719},{"x":418.97589111328125,"y":117.22710418701172},{"x":446.6479797363281,"y":117.41020202636719},{"x":474.5630798339844,"y":117.2578125},{"x":502.6095886230469,"y":117.2484359741211},{"x":530.4583129882812,"y":117.37226104736328},{"x":558.3632202148438,"y":117.33953094482422},{"x":586.5222778320312,"y":117.48817443847656},{"x":614.9005126953125,"y":116.88790130615234},{"x":643.3129272460938,"y":117.33589935302734},{"x":671.70849609375,"y":117.14772033691406},{"x":700.1260375976562,"y":117.23355102539062},{"x":728.7785034179688,"y":117.46754455566406},{"x":756.5416870117188,"y":117.7092514038086},{"x":418.66693115234375,"y":145.04176330566406},{"x":446.1064758300781,"y":145.4128875732422},{"x":474.131103515625,"y":145.261962890625},{"x":501.87713623046875,"y":145.6765899658203},{"x":530.0193481445312,"y":145.38389587402344},{"x":558.2833251953125,"y":145.2885284423828},{"x":586.0001831054688,"y":145.09837341308594},{"x":614.1900634765625,"y":145.64483642578125},{"x":643.01318359375,"y":145.65118408203125},{"x":671.2343139648438,"y":145.23851013183594},{"x":699.1350708007812,"y":145.30584716796875},{"x":728.0694580078125,"y":145.39852905273438},{"x":756.4654541015625,"y":146.0008087158203},{"x":418.1438903808594,"y":173.30149841308594},{"x":446.0181884765625,"y":173.28013610839844},{"x":473.65045166015625,"y":173.55270385742188},{"x":501.4871520996094,"y":173.34034729003906},{"x":529.5067138671875,"y":173.41859436035156},{"x":557.6668090820312,"y":173.40257263183594},{"x":585.8884887695312,"y":173.4115753173828},{"x":613.883056640625,"y":173.425537109375},{"x":641.9522705078125,"y":173.75238037109375},{"x":670.4747924804688,"y":173.89675903320312},{"x":698.9442138671875,"y":173.56527709960938},{"x":727.134765625,"y":173.60157775878906},{"x":755.8035888671875,"y":173.79051208496094},{"x":418.146484375,"y":201.0891571044922},{"x":445.4907531738281,"y":201.1538848876953},{"x":473.1720275878906,"y":200.98394775390625},{"x":501.24560546875,"y":201.3497772216797},{"x":528.890380859375,"y":201.32537841796875},{"x":557.2887573242188,"y":201.34878540039062},{"x":584.8787841796875,"y":201.71368408203125},{"x":613.1779174804688,"y":201.73947143554688},{"x":641.2566528320312,"y":201.43821716308594},{"x":669.6931762695312,"y":202.1156768798828},{"x":697.9530029296875,"y":201.84280395507812},{"x":726.70361328125,"y":202.00711059570312},{"x":754.881103515625,"y":202.20001220703125},{"x":417.7926025390625,"y":228.995361328125},{"x":445.1388854980469,"y":228.78236389160156},{"x":473.1313781738281,"y":229.28704833984375},{"x":500.91326904296875,"y":229.46128845214844},{"x":528.5372314453125,"y":229.3868408203125},{"x":556.4307250976562,"y":229.3030242919922},{"x":584.3530883789062,"y":229.9373779296875},{"x":612.498291015625,"y":229.486572265625},{"x":641.0420532226562,"y":229.8538818359375},{"x":669.474609375,"y":230.36891174316406},{"x":697.7349243164062,"y":230.12657165527344},{"x":725.6329345703125,"y":230.32789611816406},{"x":754.551513671875,"y":230.54202270507812},{"x":417.6108093261719,"y":256.345947265625},{"x":445.1260681152344,"y":256.804443359375},{"x":472.6576843261719,"y":256.8750305175781},{"x":500.3900146484375,"y":257.2099914550781},{"x":527.9927368164062,"y":257.03179931640625},{"x":555.7711791992188,"y":257.5198059082031},{"x":583.9508666992188,"y":257.41644287109375},{"x":612.1347045898438,"y":257.59344482421875},{"x":640.4732055664062,"y":257.74951171875},{"x":668.6908569335938,"y":257.92462158203125},{"x":417.3004150390625,"y":284.0661926269531},{"x":444.8813171386719,"y":284.2079162597656},{"x":472.31744384765625,"y":284.2398376464844},{"x":499.7500305175781,"y":284.4897766113281},{"x":527.6151123046875,"y":284.9800720214844},{"x":555.8385009765625,"y":285.1485595703125},{"x":583.237060546875,"y":285.53887939453125},{"x":611.50830078125,"y":285.1748046875},{"x":639.8164672851562,"y":285.6233215332031},{"x":668.410400390625,"y":286.15301513671875},{"x":416.7791748046875,"y":311.3072509765625},{"x":444.2684326171875,"y":312.04107666015625},{"x":471.98187255859375,"y":312.1766357421875},{"x":499.9118957519531,"y":312.2362976074219},{"x":527.1377563476562,"y":312.284912109375},{"x":555.1799926757812,"y":312.662353515625},{"x":582.81689453125,"y":313.17138671875},{"x":611.0717163085938,"y":313.2971496582031},{"x":639.1448364257812,"y":313.3856201171875},{"x":667.170166015625,"y":313.9883728027344},{"x":695.566650390625,"y":313.97271728515625},{"x":724.0131225585938,"y":314.1541442871094},{"x":752.0381469726562,"y":314.31488037109375}],"reprojectionErrors":[{"x":-0.10223388671875,"y":0.29369354248046875},{"x":-0.1456298828125,"y":-0.2979011535644531},{"x":0.309814453125,"y":-0.1931915283203125},{"x":-0.1947021484375,"y":0.02571868896484375},{"x":-0.194976806640625,"y":-0.0557861328125},{"x":-0.08636474609375,"y":-0.07848358154296875},{"x":-0.09820556640625,"y":-0.1709136962890625},{"x":-0.187744140625,"y":-0.09151458740234375},{"x":0.16339111328125,"y":0.04854583740234375},{"x":0.32843017578125,"y":-0.21087646484375},{"x":0.43560791015625,"y":-0.505645751953125},{"x":-0.20489501953125,"y":0.039794921875},{"x":-0.0789794921875,"y":-0.17884063720703125},{"x":-0.112823486328125,"y":-0.0561981201171875},{"x":-0.197265625,"y":-0.07073974609375},{"x":-0.00555419921875,"y":-0.212646484375},{"x":0.205810546875,"y":-0.19211578369140625},{"x":0.236328125,"y":-0.3470611572265625},{"x":0.1185302734375,"y":0.252838134765625},{"x":0.03350830078125,"y":0.0101470947265625},{"x":0.0732421875,"y":-0.05814361572265625},{"x":-0.0616455078125,"y":-0.26857757568359375},{"x":0.75048828125,"y":-0.48069000244140625},{"x":-0.16387939453125,"y":0.2025299072265625},{"x":0.155303955078125,"y":-0.1613311767578125},{"x":-0.027618408203125,"y":0.0018463134765625},{"x":0.148681640625,"y":-0.3955535888671875},{"x":0.00689697265625,"y":-0.080596923828125},{"x":-0.18096923828125,"y":0.0420684814453125},{"x":0.25140380859375,"y":0.2645721435546875},{"x":0.28143310546875,"y":-0.2444610595703125},{"x":-0.2537841796875,"y":-0.2082977294921875},{"x":0.39385986328125,"y":0.237396240234375},{"x":-0.064208984375,"y":0.2025909423828125},{"x":0.07366943359375,"y":-0.3366546630859375},{"x":0.092041015625,"y":-0.15972900390625},{"x":-0.06231689453125,"y":-0.0885467529296875},{"x":0.108154296875,"y":-0.30712890625},{"x":0.154571533203125,"y":-0.036590576171875},{"x":0.09600830078125,"y":-0.0524749755859375},{"x":-0.027587890625,"y":0.030120849609375},{"x":-0.13983154296875,"y":0.0919036865234375},{"x":0.04547119140625,"y":0.1529388427734375},{"x":0.2239990234375,"y":-0.0946502685546875},{"x":0.01446533203125,"y":-0.155548095703125},{"x":0.165771484375,"y":0.3193817138671875},{"x":-0.010009765625,"y":0.2266998291015625},{"x":-0.176910400390625,"y":-0.12823486328125},{"x":0.1605224609375,"y":-0.1008148193359375},{"x":0.2435302734375,"y":0.164642333984375},{"x":0.014404296875,"y":-0.1023101806640625},{"x":0.29180908203125,"y":0.0243377685546875},{"x":-0.10919189453125,"y":0.1065521240234375},{"x":0.3709716796875,"y":-0.1493377685546875},{"x":0.2122802734375,"y":-0.062744140625},{"x":0.34161376953125,"y":0.354278564453125},{"x":0.17828369140625,"y":-0.2040252685546875},{"x":0.254150390625,"y":0.1913909912109375},{"x":0.17431640625,"y":0.0894317626953125},{"x":-0.088653564453125,"y":-0.2919769287109375},{"x":0.209075927734375,"y":0.055267333984375},{"x":-0.057037353515625,"y":-0.3126220703125},{"x":-0.032623291015625,"y":-0.347503662109375},{"x":0.22723388671875,"y":-0.131134033203125},{"x":0.29266357421875,"y":0.0971527099609375},{"x":0.40179443359375,"y":-0.3901824951171875},{"x":0.35809326171875,"y":0.210174560546875},{"x":-0.01666259765625,"y":-0.005035400390625},{"x":-0.21527099609375,"y":-0.365447998046875},{"x":-0.1793212890625,"y":0.0340576171875},{"x":0.27862548828125,"y":-0.007598876953125},{"x":-0.171722412109375,"y":0.0247802734375},{"x":-0.08013916015625,"y":-0.257598876953125},{"x":0.077239990234375,"y":-0.15032958984375},{"x":0.1136474609375,"y":-0.3056640625},{"x":0.35693359375,"y":0.053924560546875},{"x":0.49945068359375,"y":-0.251007080078125},{"x":0.31304931640625,"y":0.037200927734375},{"x":0.1923828125,"y":0.046722412109375},{"x":-0.015625,"y":0.078887939453125},{"x":-0.03802490234375,"y":0.093658447265625},{"x":-0.125457763671875,"y":-0.1016845703125},{"x":-0.13616943359375,"y":-0.025634765625},{"x":0.079833984375,"y":0.16119384765625},{"x":0.3226318359375,"y":-0.138763427734375},{"x":-0.01727294921875,"y":-0.085723876953125},{"x":0.539794921875,"y":-0.25360107421875},{"x":0.29388427734375,"y":0.333770751953125},{"x":0.0782470703125,"y":0.10943603515625},{"x":-0.35858154296875,"y":-0.19525146484375},{"x":0.13238525390625,"y":0.1790771484375},{"x":0.17718505859375,"y":-0.2955322265625},{"x":0.07952880859375,"y":-0.171722412109375},{"x":-0.155364990234375,"y":0.02813720703125},{"x":0.1920166015625,"y":0.177886962890625},{"x":0.28619384765625,"y":-0.164947509765625},{"x":0.07110595703125,"y":0.110595703125},{"x":-0.134765625,"y":0.18902587890625},{"x":0.137451171875,"y":0.28802490234375}],"optimisedCameraToObject":{"translation":{"x":0.01402345311539138,"y":-0.13763316846046542,"z":0.368022346716543},"rotation":{"quaternion":{"W":0.9997200315395114,"X":0.016656066570157536,"Y":0.01619731616532869,"Z":0.004481175525377351}}},"cornersUsed":[true,false,false,false,true,true,false,false,true,true,true,true,true,false,true,false,false,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,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,false],"snapshotName":"img10.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img10.png"},{"locationInObjectSpace":[{"x":0.0,"y":0.0,"z":0.0},{"x":0.015011399984359741,"y":0.0,"z":-8.006768621271476E-5},{"x":0.030022799968719482,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.045034199953079224,"y":0.0,"z":-2.032487391261384E-4},{"x":0.060045599937438965,"y":0.0,"z":-2.46362091274932E-4},{"x":0.0750569999217987,"y":0.0,"z":-2.771573781501502E-4},{"x":0.09006839990615845,"y":0.0,"z":-2.956345269922167E-4},{"x":0.10507979989051819,"y":0.0,"z":-3.0179356690496206E-4},{"x":0.12009119987487793,"y":0.0,"z":-2.956345269922167E-4},{"x":0.13510259985923767,"y":0.0,"z":-2.771573781501502E-4},{"x":0.1501139998435974,"y":0.0,"z":-2.463621203787625E-4},{"x":0.16512539982795715,"y":0.0,"z":-2.032487391261384E-4},{"x":0.1801367998123169,"y":0.0,"z":-1.4781726349610835E-4},{"x":0.19514819979667664,"y":0.0,"z":-8.006768621271476E-5},{"x":0.0,"y":0.015011399984359741,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.015011399984359741,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.015011399984359741,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.015011399984359741,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.015011399984359741,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.015011399984359741,"z":-1.7752400890458375E-4},{"x":0.1801367998123169,"y":0.015011399984359741,"z":-1.2209254782646894E-4},{"x":0.19514819979667664,"y":0.015011399984359741,"z":-5.434296326711774E-5},{"x":0.0,"y":0.030022799968719482,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.10507979989051819,"y":0.030022799968719482,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.030022799968719482,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.030022799968719482,"z":-2.3142453574109823E-4},{"x":0.1501139998435974,"y":0.030022799968719482,"z":-2.006292634177953E-4},{"x":0.16512539982795715,"y":0.030022799968719482,"z":-1.5751589671708643E-4},{"x":0.1801367998123169,"y":0.030022799968719482,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.030022799968719482,"z":-3.433484380366281E-5},{"x":0.0,"y":0.045034199953079224,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.045034199953079224,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.10507979989051819,"y":0.045034199953079224,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.045034199953079224,"z":-2.3561017587780952E-4},{"x":0.13510259985923767,"y":0.045034199953079224,"z":-2.1713301248382777E-4},{"x":0.1501139998435974,"y":0.045034199953079224,"z":-1.8633775471244007E-4},{"x":0.16512539982795715,"y":0.045034199953079224,"z":-1.432243880117312E-4},{"x":0.1801367998123169,"y":0.045034199953079224,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.045034199953079224,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.060045599937438965,"z":6.859925633762032E-5},{"x":0.015011399984359741,"y":0.060045599937438965,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.060045599937438965,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.09006839990615845,"y":0.060045599937438965,"z":-2.270352706545964E-4},{"x":0.13510259985923767,"y":0.060045599937438965,"z":-2.0855810726061463E-4},{"x":0.1501139998435974,"y":0.060045599937438965,"z":-1.7776284948922694E-4},{"x":0.16512539982795715,"y":0.060045599937438965,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.060045599937438965,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.060045599937438965,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.0750569999217987,"z":7.145756535464898E-5},{"x":0.015011399984359741,"y":0.0750569999217987,"z":-8.610121767560486E-6},{"x":0.030022799968719482,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.045034199953079224,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.060045599937438965,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.0750569999217987,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.09006839990615845,"y":0.0750569999217987,"z":-2.2417696891352534E-4},{"x":0.13510259985923767,"y":0.0750569999217987,"z":-2.056998055195436E-4},{"x":0.1501139998435974,"y":0.0750569999217987,"z":-1.749045477481559E-4},{"x":0.16512539982795715,"y":0.0750569999217987,"z":-1.3179118104744703E-4},{"x":0.1801367998123169,"y":0.0750569999217987,"z":-7.635969814145938E-5},{"x":0.19514819979667664,"y":0.0750569999217987,"z":-8.610122677055188E-6},{"x":0.0,"y":0.09006839990615845,"z":6.859926361357793E-5},{"x":0.015011399984359741,"y":0.09006839990615845,"z":-1.1468424418126233E-5},{"x":0.030022799968719482,"y":0.09006839990615845,"z":-7.921799988253042E-5},{"x":0.045034199953079224,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.060045599937438965,"y":0.09006839990615845,"z":-1.7776284948922694E-4},{"x":0.0750569999217987,"y":0.09006839990615845,"z":-2.0855810726061463E-4},{"x":0.09006839990615845,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.10507979989051819,"y":0.09006839990615845,"z":-2.3319432511925697E-4},{"x":0.12009119987487793,"y":0.09006839990615845,"z":-2.270352706545964E-4},{"x":0.16512539982795715,"y":0.09006839990615845,"z":-1.3464948278851807E-4},{"x":0.1801367998123169,"y":0.09006839990615845,"z":-7.921800715848804E-5},{"x":0.19514819979667664,"y":0.09006839990615845,"z":-1.1468425327620935E-5},{"x":0.0,"y":0.10507979989051819,"z":6.002435111440718E-5},{"x":0.015011399984359741,"y":0.10507979989051819,"z":-2.0043331460328773E-5},{"x":0.030022799968719482,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.045034199953079224,"y":0.10507979989051819,"z":-1.432243880117312E-4},{"x":0.060045599937438965,"y":0.10507979989051819,"z":-1.8633775471244007E-4},{"x":0.0750569999217987,"y":0.10507979989051819,"z":-2.1713301248382777E-4},{"x":0.09006839990615845,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.10507979989051819,"y":0.10507979989051819,"z":-2.417692303424701E-4},{"x":0.12009119987487793,"y":0.10507979989051819,"z":-2.3561017587780952E-4},{"x":0.1801367998123169,"y":0.10507979989051819,"z":-8.779291238170117E-5},{"x":0.19514819979667664,"y":0.10507979989051819,"z":-2.0043333279318176E-5},{"x":0.0,"y":0.12009119987487793,"z":4.573283877107315E-5},{"x":0.015011399984359741,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.030022799968719482,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.045034199953079224,"y":0.12009119987487793,"z":-1.5751589671708643E-4},{"x":0.060045599937438965,"y":0.12009119987487793,"z":-2.006292634177953E-4},{"x":0.0750569999217987,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.09006839990615845,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.10507979989051819,"y":0.12009119987487793,"z":-2.5606073904782534E-4},{"x":0.12009119987487793,"y":0.12009119987487793,"z":-2.4990169913508E-4},{"x":0.13510259985923767,"y":0.12009119987487793,"z":-2.3142453574109823E-4},{"x":0.1801367998123169,"y":0.12009119987487793,"z":-1.020844210870564E-4},{"x":0.19514819979667664,"y":0.12009119987487793,"z":-3.433484380366281E-5},{"x":0.0,"y":0.13510259985923767,"z":2.5724722945597023E-5},{"x":0.015011399984359741,"y":0.13510259985923767,"z":-5.434296326711774E-5},{"x":0.030022799968719482,"y":0.13510259985923767,"z":-1.2209254782646894E-4},{"x":0.045034199953079224,"y":0.13510259985923767,"z":-1.7752400890458375E-4},{"x":0.060045599937438965,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.0750569999217987,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.09006839990615845,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.10507979989051819,"y":0.13510259985923767,"z":-2.760688657872379E-4},{"x":0.12009119987487793,"y":0.13510259985923767,"z":-2.6990979677066207E-4},{"x":0.13510259985923767,"y":0.13510259985923767,"z":-2.5143264792859554E-4},{"x":0.1501139998435974,"y":0.13510259985923767,"z":-2.2063739015720785E-4},{"x":0.16512539982795715,"y":0.13510259985923767,"z":-1.7752400890458375E-4}],"locationInImageSpace":[{"x":45.912513732910156,"y":293.4513854980469},{"x":70.08702087402344,"y":292.58050537109375},{"x":94.25544738769531,"y":292.20526123046875},{"x":118.8211669921875,"y":291.43115234375},{"x":143.35186767578125,"y":291.04718017578125},{"x":168.19224548339844,"y":290.39117431640625},{"x":193.18804931640625,"y":289.7140808105469},{"x":218.05084228515625,"y":289.218017578125},{"x":243.0302276611328,"y":288.5620422363281},{"x":268.2430725097656,"y":288.02716064453125},{"x":293.5174560546875,"y":287.6134338378906},{"x":318.21630859375,"y":286.6751403808594},{"x":343.91455078125,"y":286.3670959472656},{"x":369.6875915527344,"y":285.8091735839844},{"x":45.307559967041016,"y":318.34490966796875},{"x":69.48275756835938,"y":317.8504943847656},{"x":93.89199829101562,"y":316.9874267578125},{"x":118.30701446533203,"y":316.7545166015625},{"x":142.576416015625,"y":315.9037170410156},{"x":167.7653350830078,"y":315.704833984375},{"x":192.61972045898438,"y":315.087158203125},{"x":218.00047302246094,"y":314.75115966796875},{"x":242.8396453857422,"y":313.9918212890625},{"x":267.80615234375,"y":313.8359069824219},{"x":293.2418212890625,"y":313.05364990234375},{"x":318.6736755371094,"y":312.6383056640625},{"x":344.0546875,"y":312.04742431640625},{"x":369.8138122558594,"y":311.448974609375},{"x":44.61724853515625,"y":343.2845458984375},{"x":68.73464965820312,"y":342.4487609863281},{"x":93.21749877929688,"y":342.4528503417969},{"x":117.87101745605469,"y":341.92120361328125},{"x":142.54608154296875,"y":341.33502197265625},{"x":217.6804656982422,"y":340.0665588378906},{"x":242.46827697753906,"y":339.86981201171875},{"x":268.2579650878906,"y":339.1590576171875},{"x":293.4868469238281,"y":338.5624694824219},{"x":318.691650390625,"y":338.20831298828125},{"x":344.66534423828125,"y":337.5402526855469},{"x":370.0661315917969,"y":337.2402038574219},{"x":43.78841018676758,"y":368.4114990234375},{"x":68.21237182617188,"y":367.9148254394531},{"x":92.3764877319336,"y":367.2266540527344},{"x":117.1177749633789,"y":367.4410095214844},{"x":217.05767822265625,"y":365.7219543457031},{"x":242.31979370117188,"y":365.0949401855469},{"x":267.9462890625,"y":364.7621765136719},{"x":293.27239990234375,"y":364.12091064453125},{"x":318.69842529296875,"y":364.3922119140625},{"x":344.36175537109375,"y":363.35430908203125},{"x":370.3405456542969,"y":363.25732421875},{"x":43.01957321166992,"y":393.8757629394531},{"x":67.45304107666016,"y":393.8660888671875},{"x":91.76673126220703,"y":393.3406066894531},{"x":116.56475067138672,"y":392.7347717285156},{"x":191.8029327392578,"y":391.8981018066406},{"x":267.6553955078125,"y":390.5056457519531},{"x":293.4482727050781,"y":390.2162170410156},{"x":318.8267517089844,"y":389.6002502441406},{"x":345.05194091796875,"y":389.2196044921875},{"x":370.2799987792969,"y":388.9565124511719},{"x":42.088924407958984,"y":419.6934814453125},{"x":66.62399291992188,"y":419.30517578125},{"x":91.34635162353516,"y":418.9981384277344},{"x":116.11443328857422,"y":418.7382507324219},{"x":140.9706573486328,"y":418.29107666015625},{"x":165.91505432128906,"y":418.3161315917969},{"x":191.24085998535156,"y":417.8150634765625},{"x":267.75762939453125,"y":416.7295837402344},{"x":292.9714050292969,"y":416.2084655761719},{"x":318.97198486328125,"y":416.4999694824219},{"x":344.98980712890625,"y":415.9908752441406},{"x":370.959228515625,"y":415.6483154296875},{"x":41.08665084838867,"y":445.15277099609375},{"x":65.86050415039062,"y":445.00750732421875},{"x":90.35800170898438,"y":444.81573486328125},{"x":115.24223327636719,"y":444.5322265625},{"x":140.77236938476562,"y":444.4986267089844},{"x":165.47348022460938,"y":444.0738830566406},{"x":190.48826599121094,"y":443.9634094238281},{"x":216.3421173095703,"y":443.4564514160156},{"x":241.87217712402344,"y":443.8810729980469},{"x":319.0391540527344,"y":442.8015441894531},{"x":345.36285400390625,"y":442.4501037597656},{"x":371.27386474609375,"y":442.55517578125},{"x":40.004276275634766,"y":470.9002380371094},{"x":64.98116302490234,"y":471.046875},{"x":89.83122253417969,"y":470.9386291503906},{"x":114.81905364990234,"y":470.8486328125},{"x":139.87109375,"y":470.6087951660156},{"x":165.1984405517578,"y":470.384521484375},{"x":190.05921936035156,"y":469.9829406738281},{"x":215.79971313476562,"y":470.2301940917969},{"x":241.7459716796875,"y":469.9432067871094},{"x":344.93212890625,"y":468.92132568359375},{"x":371.8150329589844,"y":468.80145263671875},{"x":39.318939208984375,"y":497.3977966308594},{"x":63.952110290527344,"y":497.2239990234375},{"x":89.08946228027344,"y":497.4441223144531},{"x":113.99723052978516,"y":497.1089782714844},{"x":139.1704864501953,"y":497.3620910644531},{"x":164.7452392578125,"y":497.03472900390625},{"x":190.0146026611328,"y":496.9394836425781},{"x":215.9074249267578,"y":496.9962463378906},{"x":241.51025390625,"y":496.4624328613281},{"x":267.2361145019531,"y":496.86114501953125},{"x":345.3632507324219,"y":496.2886657714844},{"x":371.32574462890625,"y":496.030517578125},{"x":38.87373733520508,"y":524.083251953125},{"x":63.169090270996094,"y":523.8899536132812},{"x":88.2137680053711,"y":523.878662109375},{"x":113.2957992553711,"y":523.7848510742188},{"x":138.5427703857422,"y":523.7252197265625},{"x":164.08192443847656,"y":523.7083740234375},{"x":189.38546752929688,"y":523.6616821289062},{"x":214.93702697753906,"y":524.0505981445312},{"x":241.06336975097656,"y":523.7568969726562},{"x":266.7919616699219,"y":523.6596069335938},{"x":293.0932922363281,"y":523.6573486328125},{"x":318.9092712402344,"y":523.5194091796875}],"reprojectionErrors":[{"x":0.34691619873046875,"y":-0.1453857421875},{"x":0.2700347900390625,"y":0.13739013671875},{"x":0.332061767578125,"y":-0.07574462890625},{"x":0.12842559814453125,"y":0.109710693359375},{"x":0.0902252197265625,"y":-0.09515380859375},{"x":-0.12847900390625,"y":-0.02813720703125},{"x":-0.3747406005859375,"y":0.05987548828125},{"x":-0.3614501953125,"y":-0.033172607421875},{"x":-0.339569091796875,"y":0.03369140625},{"x":-0.427337646484375,"y":-0.020477294921875},{"x":-0.454315185546875,"y":-0.1956787109375},{"x":0.215118408203125,"y":0.15386962890625},{"x":0.0045166015625,"y":-0.126617431640625},{"x":-0.16302490234375,"y":-0.15692138671875},{"x":0.10835647583007812,"y":-0.1513671875},{"x":0.11272430419921875,"y":-0.18377685546875},{"x":0.01677703857421875,"y":0.1517333984375},{"x":0.04758453369140625,"y":-0.14361572265625},{"x":0.355316162109375,"y":0.17828369140625},{"x":-0.1264190673828125,"y":-0.152374267578125},{"x":-0.1448516845703125,"y":-0.0648193359375},{"x":-0.5622406005859375,"y":-0.25946044921875},{"x":-0.3119964599609375,"y":-0.031219482421875},{"x":-0.064453125,"y":-0.4068603515625},{"x":-0.162841796875,"y":-0.15655517578125},{"x":-0.135711669921875,"y":-0.27349853515625},{"x":0.0625,"y":-0.2152099609375},{"x":0.001251220703125,"y":-0.14959716796875},{"x":-0.056232452392578125,"y":-0.0301513671875},{"x":0.08875274658203125,"y":0.340972900390625},{"x":0.0029296875,"y":-0.128997802734375},{"x":-0.12010955810546875,"y":-0.06439208984375},{"x":-0.1324920654296875,"y":0.05364990234375},{"x":-0.593231201171875,"y":-0.126708984375},{"x":-0.39398193359375,"y":-0.0042724609375},{"x":-0.048065185546875,"y":-0.1251220703125},{"x":-0.3499755859375,"y":0.067108154296875},{"x":0.04052734375,"y":-0.1094970703125},{"x":-0.09383392333984375,"y":0.0799560546875},{"x":-0.17169189453125,"y":0.174957275390625},{"x":0.14586639404296875,"y":0.4598388671875},{"x":0.0206298828125,"y":-0.159423828125},{"x":-0.136627197265625,"y":-0.07568359375},{"x":-0.130096435546875,"y":0.13873291015625},{"x":0.151885986328125,"y":0.21466064453125},{"x":0.058868408203125,"y":-0.107940673828125},{"x":-0.20313644409179688,"y":0.0318603515625},{"x":-0.20587158203125,"y":-0.29620361328125},{"x":0.0476837158203125,"y":-0.11053466796875},{"x":-0.04778289794921875,"y":0.15338134765625},{"x":-0.3790283203125,"y":-0.0479736328125},{"x":-0.153656005859375,"y":0.288330078125},{"x":-0.3336181640625,"y":0.2218017578125},{"x":0.025177001953125,"y":0.479827880859375},{"x":-0.339935302734375,"y":0.500640869140625},{"x":-0.1812744140625,"y":-0.0721435546875},{"x":-0.159149169921875,"y":0.108001708984375},{"x":-0.0447845458984375,"y":-0.200103759765625},{"x":-0.179412841796875,"y":0.015380859375},{"x":-0.341949462890625,"y":0.22906494140625},{"x":0.151123046875,"y":0.45458984375},{"x":-0.017333984375,"y":-0.134979248046875},{"x":-0.079345703125,"y":0.07354736328125},{"x":0.0291748046875,"y":0.113128662109375},{"x":-0.062244415283203125,"y":0.136627197265625},{"x":-0.23332977294921875,"y":0.074798583984375},{"x":0.0103759765625,"y":0.05645751953125},{"x":0.00457763671875,"y":0.1268310546875},{"x":0.2045135498046875,"y":0.03814697265625},{"x":-0.234893798828125,"y":0.31988525390625},{"x":-0.2198944091796875,"y":-0.3330078125},{"x":0.017242431640625,"y":0.04364013671875},{"x":-0.253814697265625,"y":0.154693603515625},{"x":0.010833740234375,"y":-0.193756103515625},{"x":0.10589981079101562,"y":0.360931396484375},{"x":-0.1807861328125,"y":0.073944091796875},{"x":-0.20122528076171875,"y":0.038360595703125},{"x":-0.221221923828125,"y":-0.018951416015625},{"x":-0.168487548828125,"y":0.070068359375},{"x":-0.2553863525390625,"y":0.1400146484375},{"x":0.2585906982421875,"y":0.38372802734375},{"x":0.02581787109375,"y":-0.024932861328125},{"x":-0.2327880859375,"y":0.36041259765625},{"x":-0.13536453247070312,"y":0.026611328125},{"x":0.01006317138671875,"y":0.1278076171875},{"x":-0.2082672119140625,"y":-0.16888427734375},{"x":-0.0578155517578125,"y":0.08575439453125},{"x":-0.034912109375,"y":-0.251861572265625},{"x":-0.27685546875,"y":-0.0130615234375},{"x":-0.078125,"y":-0.0103759765625},{"x":-0.3689117431640625,"y":-0.16375732421875},{"x":-0.2371978759765625,"y":0.269317626953125},{"x":-0.09747314453125,"y":-0.234222412109375},{"x":0.143341064453125,"y":-0.001007080078125},{"x":-0.0919647216796875,"y":-0.10845947265625},{"x":-0.02437591552734375,"y":-0.02734375},{"x":0.0172119140625,"y":0.01507568359375},{"x":-0.095733642578125,"y":0.01019287109375},{"x":0.1632232666015625,"y":0.03057861328125},{"x":0.3090667724609375,"y":-0.38922119140625},{"x":0.01361083984375,"y":-0.13104248046875},{"x":0.2479248046875,"y":-0.07391357421875},{"x":0.0400390625,"y":-0.116455078125},{"x":0.446502685546875,"y":-0.028076171875}],"optimisedCameraToObject":{"translation":{"x":-0.20856964945103676,"y":-0.01379129119118382,"z":0.409820134499174},"rotation":{"quaternion":{"W":0.9982850336146795,"X":-0.04799331792822814,"Y":0.03235016911508654,"Z":-0.00878064083103941}}},"cornersUsed":[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,true,true,true,true,true,true,true,true,true,true,true,false,false,false,true,true,true,true,true,true,true,true,true,true,true,false,false,true,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,false,false,true,true,true,true,true,true,true,true,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,false,false],"snapshotName":"img11.png","snapshotDataLocation":"file:///opt/photonvision/photonvision_config/calibration/4247f233-e48e-4cb7-b01a-7ce6bc7bf7cb/imgs/800x600/img11.png"}],"calobjectSize":{"width":14.0,"height":10.0},"calobjectSpacing":0.0150114,"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 dabec03..f2590b9 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -6,6 +6,7 @@ package org.team2342.frc; +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; @@ -24,7 +25,7 @@ public final class Constants { public static final Mode CURRENT_MODE = Mode.REAL; - public static final boolean TUNING = true; + public static final boolean TUNING = false; public static enum Mode { /** Running on a real robot. */ @@ -38,18 +39,36 @@ public static enum Mode { } public static final class VisionConstants { - public static final String CAMERA_NAME = "left_arducam"; + public static final String SWERVE_CAMERA_NAME = "swerve_arducam"; + public static final String SHOOTER_CAMERA_NAME = "shooter_arducam"; - public static final Transform3d CAMERA_TRANSFORM = + public static final Transform3d SWERVE_CAMERA_TRANSFORM = new Transform3d( new Translation3d( - Units.inchesToMeters(7.883), - Units.inchesToMeters(-10.895), + Units.inchesToMeters(-7.883), + Units.inchesToMeters(10.895), Units.inchesToMeters(8)), - new Rotation3d(0, Units.degreesToRadians(-22.0), Units.degreesToRadians(90 - 61.475))); + new Rotation3d( + 0, Units.degreesToRadians(-22.0), Units.degreesToRadians(-(90 + 61.475)))); - public static final CameraParameters LEFT_PARAMETERS = - CameraParameters.loadFromName(CAMERA_NAME, 800, 600).withTransform(CAMERA_TRANSFORM); + public static final Transform3d SHOOTER_CAMERA_TRANSFORM = + new Transform3d( + new Translation3d( + Units.inchesToMeters(-13.255), + Units.inchesToMeters(11.9), + Units.inchesToMeters(14.755)), + new Rotation3d( + 0, + Units.degreesToRadians((90 - 63.435 + 180)), + Units.degreesToRadians(-119.745 + 90))); + + public static final CameraParameters SWERVE_CAMERA_PARAMETERS = + CameraParameters.loadFromName(SWERVE_CAMERA_NAME, 800, 600) + .withTransform(SWERVE_CAMERA_TRANSFORM); + + public static final CameraParameters SHOOTER_CAMERA_PARAMETERS = + CameraParameters.loadFromName(SHOOTER_CAMERA_NAME, 800, 600) + .withTransform(SHOOTER_CAMERA_TRANSFORM); // Basic filtering thresholds public static final double MAX_AMBIGUITY = 0.1; @@ -115,44 +134,64 @@ public static final class DriveConstants { public static final double ODOMETRY_FREQUENCY = IS_CANFD ? 250.0 : 100.0; } - public static final class IndexerConstants { + public static final class KickerConstants { public static final double RUN_VOLTAGE = 7.0; - public static final double FEEDER_VOLTAGE = 7.0; - public static final double RUN_CURRENT = 40.0; - public static final double FEEDER_CURRENT = 40.0; - - public static final MotorConfig INDEXER_WHEEL_CONFIG = + public static final MotorConfig KICKER_CONFIG = new MotorConfig() - .withMotorInverted(false) + .withMotorInverted(true) .withSupplyCurrentLimit(30.0) .withStatorCurrentLimit(40.0) .withIdleMode(MotorConfig.IdleMode.BRAKE); + } + + public static final class ConductorConstants { + public static final double TRENCH_BUFFER = 0.1; + } + + public static final class IndexerConstants { + public static final double RUN_VOLTAGE = 8.0; + public static final double FEEDER_VOLTAGE = 10.0; + + public static final double RUN_CURRENT = 30.0; + public static final double FEEDER_CURRENT = 30.0; public static final MotorConfig INDEXER_BELT_CONFIG = new MotorConfig() .withMotorInverted(false) .withSupplyCurrentLimit(30.0) - .withStatorCurrentLimit(40.0) + .withStatorCurrentLimit(70.0) .withIdleMode(MotorConfig.IdleMode.BRAKE); public static final MotorConfig INDEXER_FEEDER_CONFIG = new MotorConfig() - .withMotorInverted(true) + .withMotorInverted(false) .withSupplyCurrentLimit(30.0) - .withStatorCurrentLimit(40.0) + .withStatorCurrentLimit(70.0) .withIdleMode(MotorConfig.IdleMode.BRAKE); + + public static final DCMotor INDEXER_BELT_SIM_MOTOR = DCMotor.getKrakenX60(1); + public static final DCMotorSim INDEXER_BELT_SIM = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(INDEXER_BELT_SIM_MOTOR, 0.003, 1), + INDEXER_BELT_SIM_MOTOR); + + public static final DCMotor INDEXER_FEEDER_SIM_MOTOR = DCMotor.getKrakenX60(1); + public static final DCMotorSim INDEXER_FEEDER_SIM = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(INDEXER_FEEDER_SIM_MOTOR, 0.0025, 1), + INDEXER_FEEDER_SIM_MOTOR); } public static final class IntakeConstants { - public static final double RUN_VOLTAGE = 8.0; - public static final double RUN_CURRENT = 40.0; + public static final double RUN_VOLTAGE = 7.0; + public static final double RUN_CURRENT = 10.0; public static final MotorConfig INTAKE_WHEELS_MOTOR_CONFIG = new MotorConfig() .withMotorInverted(true) - .withSupplyCurrentLimit(40.0) - .withStatorCurrentLimit(50.0) - .withIdleMode(IdleMode.BRAKE); + .withSupplyCurrentLimit(30.0) + .withStatorCurrentLimit(70.0) + .withIdleMode(IdleMode.COAST); public static final DCMotor INTAKE_WHEELS_SIM_MOTOR = DCMotor.getKrakenX60(1); public static final DCMotorSim INTAKE_WHEEL_SIM = @@ -165,15 +204,23 @@ public static final class ShooterConstants { public static final double FLYWHEEL_GEAR_RATIO = 23.0 / 24.0; public static final double FLYWHEEL_RADIUS_METERS = Units.inchesToMeters(2.0); - public static final PIDFFConfigs FLYWHEEL_PID_CONFIGS = new PIDFFConfigs().withKP(2.2); + public static final double IDLE_SPEED = 15.0; + + public static final PIDFFConfigs FLYWHEEL_PID_CONFIGS = + new PIDFFConfigs() + .withKP(0.5) + .withKI(0.0) + .withKS(Units.radiansToRotations(0.1824)) + .withKV(Units.radiansToRotations(0.020077)) + .withKA(Units.radiansToRotations(0.0037398)); public static final SmartMotorConfig FLYWHEEL_CONFIG = new SmartMotorConfig() - .withControlType(ControlType.PROFILED_VELOCITY) + .withControlType(ControlType.VELOCITY) .withGearRatio(FLYWHEEL_GEAR_RATIO) .withMotorInverted(false) - .withSupplyCurrentLimit(50) - .withProfileConstraintsRad(new TrapezoidProfile.Constraints(1000, 1000)) - .withStatorCurrentLimit(70); + .withSupplyCurrentLimit(40) + .withStatorCurrentLimit(70) + .withProfileConstraintsRad(new TrapezoidProfile.Constraints(1000, 1000)); public static final DCMotor FLYWHEEL_SIM_MOTOR = DCMotor.getKrakenX60(1); public static final DCMotorSim FLYWHEEL_SIM = new DCMotorSim( @@ -192,10 +239,10 @@ public static final class ShooterConstants { .withGearRatio(ENCODER_TO_HOOD) .withControlType(ControlType.PROFILED_POSITION) .withIdleMode(IdleMode.BRAKE) - .withSupplyCurrentLimit(40) + .withSupplyCurrentLimit(30.0) .withFeedbackConfig( FeedbackConfig.fused( - CANConstants.HOOD_ENCODER_ID, KRAKEN_TO_ENCODER, 0.3155, false)) + CANConstants.HOOD_ENCODER_ID, KRAKEN_TO_ENCODER, 0.662 / 2, false)) .withProfileConstraintsRad( new TrapezoidProfile.Constraints( Units.degreesToRadians(1800), Units.degreesToRadians(1800))); @@ -208,6 +255,40 @@ public static final class ShooterConstants { HOOD_SIM_MOTOR); } + public static final class TurretConstants { + public static final Transform3d TURRET_TRANSFORM = + new Transform3d( + new Translation3d( + Units.inchesToMeters(-4.960), + Units.inchesToMeters(5.997), + Units.inchesToMeters(14.823)), + new Rotation3d(Rotation2d.k180deg)); + + public static final double AT_POSITION_THRESHOLD = 0.01; + + public static final double STARTING_ANGLE = Units.degreesToRadians(0); + public static final double MIN_TURRET_ANGLE = Units.degreesToRadians(-90); + public static final double MAX_TURRET_ANGLE = Units.degreesToRadians(90); + + public static final double GEAR_RATIO = (46.0 / 12.0) * (100.0 / 10.0); + + public static final SmartMotorConfig TURRET_CONFIG = + new SmartMotorConfig() + .withControlType(ControlType.PROFILED_POSITION) + .withGearRatio(GEAR_RATIO) + .withIdleMode(IdleMode.BRAKE) + .withProfileConstraintsRad(new TrapezoidProfile.Constraints(Math.PI, Math.PI)) + .withSupplyCurrentLimit(40); + + public static final PIDFFConfigs PID_CONFIG = new PIDFFConfigs().withKP(100).withKI(10); + + public static final DCMotor TURRET_SIM_MOTOR = DCMotor.getKrakenX60(1); + public static final DCMotorSim TURRET_SIM = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(TURRET_SIM_MOTOR, 0.003, 100.0 / 16.0), + TURRET_SIM_MOTOR); + } + public static final class CANConstants { public static final int PIGEON_ID = 13; public static final int[] FL_IDS = {1, 5, 9}; @@ -225,7 +306,10 @@ public static final class CANConstants { public static final int INDEXER_WHEEL_ID = 20; public static final int INDEXER_BELT_ID = 21; - public static final int INDEXER_FEEDER_ID = 22; + + public static final int KICKER_ID = 22; + + public static final int TURRET_ID = 23; public static final int PDH_ID = 62; } diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index f784b3c..b92fac6 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -29,6 +29,7 @@ import org.littletonrobotics.junction.networktables.NT4Publisher; import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; +import org.team2342.frc.util.FiringSolver; import org.team2342.frc.util.PhoenixUtils; import org.team2342.lib.logging.ExecutionLogger; @@ -158,6 +159,7 @@ public void robotPeriodic() { ExecutionLogger.log("Commands"); robotContainer.updateAlerts(); + FiringSolver.getInstance().clearCachedSolution(); ExecutionLogger.log("RobotPeriodic"); } @@ -175,6 +177,10 @@ public void disabledExit() { @Override public void autonomousInit() { + robotContainer.getDrive().calculateVisionHeadingOffset(); + + CommandScheduler.getInstance().schedule(robotContainer.getWheels().out().withTimeout(1)); + autonomousCommand = robotContainer.getAutonomousCommand(); if (autonomousCommand != null) { diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index a4893d4..a0b5475 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -10,25 +10,32 @@ import com.pathplanner.lib.auto.NamedCommands; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.Trigger; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import lombok.Getter; import org.littletonrobotics.junction.LoggedPowerDistribution; import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; import org.photonvision.PhotonPoseEstimator.PoseStrategy; import org.team2342.frc.Constants.CANConstants; +import org.team2342.frc.Constants.ConductorConstants; import org.team2342.frc.Constants.DriveConstants; import org.team2342.frc.Constants.IndexerConstants; import org.team2342.frc.Constants.IntakeConstants; import org.team2342.frc.Constants.PivotConstants; import org.team2342.frc.Constants.ShooterConstants; +import org.team2342.frc.Constants.TurretConstants; import org.team2342.frc.Constants.VisionConstants; import org.team2342.frc.commands.DriveCommands; +import org.team2342.frc.commands.RotationLockedDrive; +import org.team2342.frc.subsystems.Conductor; +import org.team2342.frc.subsystems.Conductor.ConductorState; import org.team2342.frc.subsystems.drive.Drive; import org.team2342.frc.subsystems.drive.GyroIO; import org.team2342.frc.subsystems.drive.GyroIOPigeon2; @@ -40,17 +47,21 @@ import org.team2342.frc.subsystems.intake.Wheels; import org.team2342.frc.subsystems.shooter.Flywheel; import org.team2342.frc.subsystems.shooter.Hood; +import org.team2342.frc.subsystems.shooter.Turret; import org.team2342.frc.subsystems.vision.Vision; import org.team2342.frc.subsystems.vision.VisionIO; import org.team2342.frc.subsystems.vision.VisionIOPhoton; import org.team2342.frc.subsystems.vision.VisionIOSim; +import org.team2342.frc.util.FieldConstants; +import org.team2342.frc.util.FiringSolver; import org.team2342.lib.motors.dumb.DumbMotorIO; import org.team2342.lib.motors.dumb.DumbMotorIOSim; import org.team2342.lib.motors.dumb.DumbMotorIOTalonFX; -import org.team2342.lib.motors.dumb.DumbMotorIOTalonFXFOC; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOSim; import org.team2342.lib.motors.smart.SmartMotorIOTalonFX; +import org.team2342.lib.pidff.PIDFFConfigs; +import org.team2342.lib.util.AllianceUtils; import org.team2342.lib.util.EnhancedXboxController; public class RobotContainer { @@ -61,6 +72,9 @@ public class RobotContainer { @Getter private final Wheels wheels; @Getter private final Flywheel flywheel; @Getter private final Hood hood; + @Getter private final Turret turret; + + @Getter private final Conductor conductor; private final LoggedDashboardChooser autoChooser; @@ -68,8 +82,17 @@ public class RobotContainer { private final EnhancedXboxController driverController = new EnhancedXboxController(0, DriveConstants.CONTROLLER_DEADBAND); + @Getter + private final EnhancedXboxController operatorController = + new EnhancedXboxController(1, DriveConstants.CONTROLLER_DEADBAND); + private final Alert driverControllerAlert = new Alert("Driver controller is disconnected!", AlertType.kError); + private final Alert operatorControllerAlert = + new Alert("Operator controller is disconnected!", AlertType.kError); + + private final Trigger trenchTrigger; + private final Trigger allianceZoneTrigger; public RobotContainer() { switch (Constants.CURRENT_MODE) { @@ -86,39 +109,28 @@ public RobotContainer() { drive::addVisionMeasurement, drive::getTimestampedHeading, new VisionIOPhoton( - VisionConstants.LEFT_PARAMETERS, + VisionConstants.SWERVE_CAMERA_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); - pivot = - new Pivot( - new DumbMotorIOTalonFX( - CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); - indexer = - new Indexer( - new DumbMotorIOTalonFXFOC( - CANConstants.INDEXER_WHEEL_ID, IndexerConstants.INDEXER_WHEEL_CONFIG), - new DumbMotorIOTalonFXFOC( - CANConstants.INDEXER_BELT_ID, IndexerConstants.INDEXER_BELT_CONFIG), - new DumbMotorIOTalonFXFOC( - CANConstants.INDEXER_FEEDER_ID, IndexerConstants.INDEXER_WHEEL_CONFIG)); - - wheels = - new Wheels( - new DumbMotorIOTalonFXFOC( - CANConstants.INTAKE_WHEEL_MOTOR_ID, - IntakeConstants.INTAKE_WHEELS_MOTOR_CONFIG)); + turret = + new Turret( + new SmartMotorIOTalonFX( + CANConstants.TURRET_ID, + TurretConstants.TURRET_CONFIG.withPIDFFConfigs(TurretConstants.PID_CONFIG))); flywheel = new Flywheel( new SmartMotorIOTalonFX( CANConstants.FLYWHEEL_MOTOR_ID, ShooterConstants.FLYWHEEL_CONFIG.withPIDFFConfigs( ShooterConstants.FLYWHEEL_PID_CONFIGS))); - hood = - new Hood( - new SmartMotorIOTalonFX( - CANConstants.HOOD_MOTOR_ID, - ShooterConstants.HOOD_MOTOR_CONFIG.withPIDFFConfigs( - ShooterConstants.HOOD_MOTOR_PID_CONFIGS))); + + indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}); + wheels = new Wheels(new DumbMotorIO() {}); + pivot = + new Pivot( + new DumbMotorIOTalonFX( + CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); + hood = new Hood(new SmartMotorIO() {}); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); break; @@ -136,13 +148,22 @@ public RobotContainer() { drive::addVisionMeasurement, drive::getTimestampedHeading, new VisionIOSim( - VisionConstants.LEFT_PARAMETERS, + VisionConstants.SWERVE_CAMERA_PARAMETERS, + PoseStrategy.CONSTRAINED_SOLVEPNP, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, + drive::getRawOdometryPose), + new VisionIOSim( + VisionConstants.SHOOTER_CAMERA_PARAMETERS, PoseStrategy.CONSTRAINED_SOLVEPNP, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, drive::getRawOdometryPose)); - pivot = new Pivot(new DumbMotorIO() {}); - - indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}, new DumbMotorIO() {}); + indexer = + new Indexer( + new DumbMotorIOSim( + IndexerConstants.INDEXER_BELT_SIM_MOTOR, IndexerConstants.INDEXER_BELT_SIM), + new DumbMotorIOSim( + IndexerConstants.INDEXER_FEEDER_SIM_MOTOR, + IndexerConstants.INDEXER_FEEDER_SIM)); wheels = new Wheels( @@ -151,17 +172,21 @@ public RobotContainer() { flywheel = new Flywheel( new SmartMotorIOSim( - ShooterConstants.FLYWHEEL_CONFIG, + ShooterConstants.FLYWHEEL_CONFIG.withPIDFFConfigs(new PIDFFConfigs().withKP(1)), ShooterConstants.FLYWHEEL_SIM_MOTOR, ShooterConstants.FLYWHEEL_SIM, 1)); hood = new Hood( new SmartMotorIOSim( - ShooterConstants.HOOD_MOTOR_CONFIG, + ShooterConstants.HOOD_MOTOR_CONFIG.withPIDFFConfigs( + new PIDFFConfigs().withKP(1)), ShooterConstants.HOOD_SIM_MOTOR, ShooterConstants.HOOD_SIM, 1)); + turret = new Turret(new SmartMotorIO() {}); + pivot = new Pivot(new DumbMotorIO() {}); + break; default: @@ -178,15 +203,18 @@ public RobotContainer() { drive::getTimestampedHeading, new VisionIO() {}, new VisionIO() {}); - pivot = new Pivot(new DumbMotorIO() {}); - indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}, new DumbMotorIO() {}); + indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}); wheels = new Wheels(new DumbMotorIO() {}); + pivot = new Pivot(new DumbMotorIO() {}); flywheel = new Flywheel(new SmartMotorIO() {}); hood = new Hood(new SmartMotorIO() {}); + turret = new Turret(new SmartMotorIO() {}); break; } + conductor = new Conductor(flywheel, hood, drive::getPose, drive::getChassisSpeeds); + configureNamedCommands(); autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); @@ -194,12 +222,79 @@ public RobotContainer() { if (Constants.TUNING) setupDevelopmentRoutines(); + autoChooser.addOption( + "scuffed wall", + Commands.run(() -> drive.runVelocity(new ChassisSpeeds(1, 0, 0)), drive) + .alongWith(conductor.runState(ConductorState.WARM_UP)) + .withTimeout(1) + .andThen( + conductor + .goToState(ConductorState.TRACKED_FIRING) + .andThen(conductor.runState(ConductorState.TRACKED_FIRING)) + .alongWith(indexer.feed()) + .alongWith( + DriveCommands.joystickDriveAtAngle( + drive, + () -> 0, + () -> 0, + () -> + FiringSolver.getInstance() + .calculate(drive.getChassisSpeeds(), drive.getPose()) + .turretAngle())))); + + autoChooser.addOption( + "wait n fire", + conductor + .runState(ConductorState.WARM_UP) + .alongWith( + DriveCommands.joystickDriveAtAngle( + drive, + () -> 0, + () -> 0, + () -> + FiringSolver.getInstance() + .calculate(drive.getChassisSpeeds(), drive.getPose()) + .turretAngle())) + .withTimeout(1) + .andThen( + conductor + .goToState(ConductorState.TRACKED_FIRING) + .andThen(conductor.runState(ConductorState.TRACKED_FIRING)) + .alongWith(indexer.feed()) + .alongWith( + DriveCommands.joystickDriveAtAngle( + drive, + () -> 0, + () -> 0, + () -> + FiringSolver.getInstance() + .calculate(drive.getChassisSpeeds(), drive.getPose()) + .turretAngle())))); + SmartDashboard.putData( "Calculate Vision Heading Offset", Commands.runOnce(() -> drive.calculateVisionHeadingOffset()) .alongWith(Commands.print("Calculated Vision Offset")) .ignoringDisable(true)); + trenchTrigger = + new Trigger( + () -> + withinBounds( + drive.getPose().getX(), + AllianceUtils.flipToAlliance(FieldConstants.LeftBump.nearLeftCorner).getX() + + ConductorConstants.TRENCH_BUFFER, + AllianceUtils.flipToAlliance(FieldConstants.LeftBump.farLeftCorner).getX() + - ConductorConstants.TRENCH_BUFFER)); + allianceZoneTrigger = + new Trigger( + () -> + withinBounds( + drive.getPose().getX(), + AllianceUtils.flipToAlliance(Pose2d.kZero).getX(), + AllianceUtils.flipToAlliance(FieldConstants.LeftBump.nearLeftCorner).getX() + + ConductorConstants.TRENCH_BUFFER)); + configureBindings(); } @@ -209,13 +304,14 @@ private void configureNamedCommands() { private void configureBindings() { // Basic drive controls - // drive.setDefaultCommand( - // new RotationLockedDrive( - // drive, - // () -> -driverController.getLeftY(), - // () -> -driverController.getLeftX(), - // () -> -driverController.getRightX())); - hood.setDefaultCommand(hood.holdAngle(() -> driverController.getLeftY() * -1 / 0.273)); + drive.setDefaultCommand( + new RotationLockedDrive( + drive, + () -> -driverController.getLeftY(), + () -> -driverController.getLeftX(), + () -> -driverController.getRightX())); + + driverController.x().whileTrue(Commands.run(drive::stopWithX, drive)); driverController .b() @@ -227,10 +323,53 @@ private void configureBindings() { drive) .ignoringDisable(true)); + driverController.leftTrigger().whileTrue(wheels.in()).onFalse(wheels.stop()); + + // Shooting Controls + driverController + .rightBumper() + .whileTrue( + conductor + .goToState(ConductorState.BUMPER_SHOT) + .andThen(conductor.runState(ConductorState.BUMPER_SHOT).alongWith(indexer.feed()))) + .onFalse(indexer.stop()); + driverController - .leftTrigger() - .whileTrue(indexer.feed().alongWith(wheels.inAmps()).alongWith(flywheel.shoot(20))) - .onFalse(indexer.stop().alongWith(wheels.stop()).alongWith(flywheel.stop())); + .rightTrigger() + .whileTrue( + conductor + .goToState(ConductorState.TRACKED_FIRING) + .andThen( + conductor.runState(ConductorState.TRACKED_FIRING).alongWith(indexer.feed())) + .alongWith( + DriveCommands.joystickDriveAtAngle( + drive, + () -> -driverController.getLeftY(), + () -> -driverController.getLeftX(), + () -> + FiringSolver.getInstance() + .calculate(drive.getChassisSpeeds(), drive.getPose()) + .turretAngle()))) + .onFalse(indexer.stop()); + + // Operator Overrides + operatorController.povRight().whileTrue(indexer.feed()).onFalse(indexer.stop()); + operatorController.povLeft().whileTrue(indexer.out()).onFalse(indexer.stop()); + + operatorController.leftBumper().whileTrue(wheels.out()).onFalse(wheels.stop()); + operatorController.leftTrigger().whileTrue(wheels.in()).onFalse(wheels.stop()); + + operatorController.rightTrigger().whileTrue(conductor.runState(ConductorState.OVERRIDE_25)); + + operatorController.rightBumper().whileTrue(conductor.runState(ConductorState.OVERRIDE_23)); + + // Location Triggers + trenchTrigger + .and(driverController.rightTrigger().negate().and(driverController.rightBumper().negate())) + .whileTrue(conductor.runState(ConductorState.TRENCH)); + allianceZoneTrigger + .and(driverController.rightTrigger().negate().and(driverController.rightBumper().negate())) + .whileTrue(conductor.runState(ConductorState.WARM_UP)); } public Command getAutonomousCommand() { @@ -253,6 +392,17 @@ private void setupDevelopmentRoutines() { autoChooser.addOption( "Drive SysId (Dynamic Reverse)", drive.sysIdDynamic(SysIdRoutine.Direction.kReverse)); + autoChooser.addOption( + "Flywheel SysId (Quasistatic Forward)", + flywheel.sysIdQuasistatic(SysIdRoutine.Direction.kForward)); + autoChooser.addOption( + "Flywheel SysId (Quasistatic Reverse)", + flywheel.sysIdQuasistatic(SysIdRoutine.Direction.kReverse)); + autoChooser.addOption( + "Flywheel SysId (Dynamic Forward)", flywheel.sysIdDynamic(SysIdRoutine.Direction.kForward)); + autoChooser.addOption( + "Flywheel SysId (Dynamic Reverse)", flywheel.sysIdDynamic(SysIdRoutine.Direction.kReverse)); + SmartDashboard.putData( "Print Encoder Zeros", Commands.runOnce(() -> drive.printModuleAbsoluteAngles()).ignoringDisable(true)); @@ -260,5 +410,10 @@ private void setupDevelopmentRoutines() { public void updateAlerts() { driverControllerAlert.set(!driverController.isConnected()); + operatorControllerAlert.set(!operatorController.isConnected()); + } + + private boolean withinBounds(double value, double bound1, double bound2) { + return value <= Math.max(bound1, bound2) && value >= Math.min(bound1, bound2); } } diff --git a/src/main/java/org/team2342/frc/subsystems/Conductor.java b/src/main/java/org/team2342/frc/subsystems/Conductor.java new file mode 100644 index 0000000..7b3e666 --- /dev/null +++ b/src/main/java/org/team2342/frc/subsystems/Conductor.java @@ -0,0 +1,185 @@ +// Copyright (c) 2026 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; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import java.util.function.Supplier; +import lombok.experimental.Delegate; +import org.team2342.frc.subsystems.shooter.Flywheel; +import org.team2342.frc.subsystems.shooter.Hood; +import org.team2342.frc.util.FiringSolver; +import org.team2342.lib.fsm.StateMachine; +import org.team2342.lib.logging.ExecutionLogger; + +public class Conductor extends SubsystemBase { + + public enum ConductorState { + UNDETERMINED, + DISABLED, + TRENCH, + BUMPER_SHOT, + WARM_UP, + TRACKED_FIRING, + OVERRIDE_25, + OVERRIDE_23; + } + + @Delegate(types = FSMDelegate.class) + private final StateMachine fsm = + new StateMachine( + "Conductor", + ConductorState.UNDETERMINED, + () -> ConductorState.DISABLED, + ConductorState.class); + + private final Flywheel flywheel; + private final Hood hood; + + private final Supplier poseSupplier; + private final Supplier velocitySupplier; + + public Conductor( + Flywheel flywheel, + Hood hood, + Supplier poseSupplier, + Supplier velocitySupplier) { + this.flywheel = flywheel; + this.hood = hood; + + this.poseSupplier = poseSupplier; + this.velocitySupplier = velocitySupplier; + + setupStateCommands(); + setupTransitions(); + + enable(); + + setDefaultCommand(runState(ConductorState.DISABLED)); + } + + @Override + public void periodic() { + fsm.periodic(); + ExecutionLogger.log("Conductor"); + } + + public Command runState(ConductorState state) { + return run(() -> fsm.requestTransition(state)); + } + + public Command goToState(ConductorState state) { + return fsm.requestTransitionCommand(state).withName("Conductor Switch To " + state.name()); + } + + public Command waitForState(ConductorState state) { + return fsm.waitForState(state).withName("Conductor Wait For " + state.name()); + } + + private void setupStateCommands() { + fsm.addStateCommand(ConductorState.DISABLED, hood.stop().alongWith(flywheel.stop())); + + fsm.addStateCommand(ConductorState.TRENCH, hood.holdAngle(0.0)); + + fsm.addStateCommand( + ConductorState.BUMPER_SHOT, + flywheel + .shoot(FiringSolver.BUMPER_SHOT.wheelSpeed()) + .alongWith(hood.holdAngle(FiringSolver.BUMPER_SHOT.hoodAngle()))); + + fsm.addStateCommand( + ConductorState.WARM_UP, + hood.holdAngle( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .hoodAngle()) + .deadlineFor(flywheel.warmUp())); + + fsm.addStateCommand( + ConductorState.TRACKED_FIRING, + hood.holdAngle( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .hoodAngle()) + .deadlineFor( + flywheel.shoot( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .wheelSpeed()))); + + fsm.addStateCommand(ConductorState.OVERRIDE_25, flywheel.shoot(25.0)); + + fsm.addStateCommand(ConductorState.OVERRIDE_23, flywheel.shoot(23.0)); + } + + private void setupTransitions() { + fsm.addOmniTransition(ConductorState.DISABLED); + + fsm.addOmniTransition(ConductorState.TRENCH, hood.goToAngle(0.0)); + + fsm.addOmniTransition( + ConductorState.BUMPER_SHOT, + hood.holdAngle(FiringSolver.BUMPER_SHOT.hoodAngle()) + .withTimeout(0.5) + .deadlineFor(flywheel.shoot(FiringSolver.BUMPER_SHOT.wheelSpeed()))); + + fsm.addOmniTransition( + ConductorState.WARM_UP, + hood.holdAngle( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .hoodAngle()) + .withTimeout(0.5) + .deadlineFor(flywheel.warmUp())); + + fsm.addOmniTransition( + ConductorState.TRACKED_FIRING, + hood.holdAngle( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .hoodAngle()) + .withTimeout(0.5) + .deadlineFor( + flywheel.shoot( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .wheelSpeed()))); + fsm.addOmniTransition( + ConductorState.OVERRIDE_25, + hood.holdAngle( + () -> + FiringSolver.getInstance() + .calculate(velocitySupplier.get(), poseSupplier.get()) + .hoodAngle()) + .withTimeout(0.5) + .deadlineFor(flywheel.shoot(25.0))); + + fsm.addOmniTransition(ConductorState.OVERRIDE_23, flywheel.shoot(23.0)); + } + + public Command makeShooterCommand(double flywheelMetersPerSec, double hoodAngle) { + return hood.holdAngle(hoodAngle).alongWith(flywheel.shoot(flywheelMetersPerSec)); + } + + public interface FSMDelegate { + String dot(); + + void enable(); + + void disable(); + + boolean isEnabled(); + } +} 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 3733381..09426cf 100644 --- a/src/main/java/org/team2342/frc/subsystems/drive/Drive.java +++ b/src/main/java/org/team2342/frc/subsystems/drive/Drive.java @@ -309,7 +309,7 @@ private SwerveModulePosition[] getModulePositions() { /** Returns the measured chassis speeds of the robot. */ @AutoLogOutput(key = "SwerveChassisSpeeds/Measured") - private ChassisSpeeds getChassisSpeeds() { + public ChassisSpeeds getChassisSpeeds() { return kinematics.toChassisSpeeds(getModuleStates()); } diff --git a/src/main/java/org/team2342/frc/subsystems/indexer/Indexer.java b/src/main/java/org/team2342/frc/subsystems/indexer/Indexer.java index 5c6e80c..b2b6f4a 100644 --- a/src/main/java/org/team2342/frc/subsystems/indexer/Indexer.java +++ b/src/main/java/org/team2342/frc/subsystems/indexer/Indexer.java @@ -17,74 +17,62 @@ import org.team2342.lib.motors.dumb.DumbMotorIOInputsAutoLogged; public class Indexer extends SubsystemBase { - private final DumbMotorIO wheelMotor; private final DumbMotorIO beltMotor; - private final DumbMotorIO feederMotor; private final DumbMotorIOInputsAutoLogged wheelMotorInputs = new DumbMotorIOInputsAutoLogged(); private final DumbMotorIOInputsAutoLogged beltMotorInputs = new DumbMotorIOInputsAutoLogged(); - private final DumbMotorIOInputsAutoLogged feederMotorInputs = new DumbMotorIOInputsAutoLogged(); private final Alert wheelMotorAlert = new Alert("Indexer Wheel Motor is diconnected", AlertType.kError); private final Alert beltMotorAlert = new Alert("Indexer Belt Motor is diconnected", AlertType.kError); - private final Alert feederMotorAlert = - new Alert("Indexer Feeder Motor is diconnected", AlertType.kError); - public Indexer(DumbMotorIO wheelMotor, DumbMotorIO beltMotor, DumbMotorIO feederMotor) { - this.wheelMotor = wheelMotor; + public Indexer(DumbMotorIO wheelMotor, DumbMotorIO beltMotor) { this.beltMotor = beltMotor; - this.feederMotor = feederMotor; setName("Indexer"); setDefaultCommand( run( () -> { - wheelMotor.runVoltage(0.0); beltMotor.runVoltage(0.0); - feederMotor.runVoltage(0.0); })); } @Override public void periodic() { - wheelMotor.updateInputs(wheelMotorInputs); beltMotor.updateInputs(beltMotorInputs); - feederMotor.updateInputs(feederMotorInputs); - Logger.processInputs("Indexer/WheelMotor", wheelMotorInputs); Logger.processInputs("Indexer/BeltMotor", beltMotorInputs); - Logger.processInputs("Indexer/FeederMotor", feederMotorInputs); - wheelMotorAlert.set(!wheelMotorInputs.connected); beltMotorAlert.set(!beltMotorInputs.connected); - feederMotorAlert.set(!feederMotorInputs.connected); ExecutionLogger.log("Indexer"); } public Command load() { return run(() -> { - wheelMotor.runTorqueCurrent(IndexerConstants.RUN_CURRENT); + beltMotor.runVoltage(IndexerConstants.RUN_VOLTAGE); }) - .withName("Indexer Load"); + .withName("Indexer Feed"); } public Command feed() { return run(() -> { - wheelMotor.runTorqueCurrent(IndexerConstants.RUN_CURRENT); beltMotor.runTorqueCurrent(IndexerConstants.RUN_CURRENT); - feederMotor.runTorqueCurrent(IndexerConstants.RUN_CURRENT); }) .withName("Indexer Feed"); } + public Command out() { + return run(() -> { + beltMotor.runVoltage(-IndexerConstants.RUN_VOLTAGE); + }) + .withName("Indexer Out"); + } + public Command stop() { return runOnce( () -> { - wheelMotor.runVoltage(0.0); beltMotor.runVoltage(0.0); - feederMotor.runVoltage(0.0); }) .withName("Indexer Stop"); } diff --git a/src/main/java/org/team2342/frc/subsystems/kicker/Kicker.java b/src/main/java/org/team2342/frc/subsystems/kicker/Kicker.java new file mode 100644 index 0000000..49dfafe --- /dev/null +++ b/src/main/java/org/team2342/frc/subsystems/kicker/Kicker.java @@ -0,0 +1,60 @@ +// Copyright (c) 2026 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.kicker; + +import edu.wpi.first.wpilibj.Alert; +import edu.wpi.first.wpilibj.Alert.AlertType; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; +import org.team2342.frc.Constants.KickerConstants; +import org.team2342.lib.logging.ExecutionLogger; +import org.team2342.lib.motors.dumb.DumbMotorIO; +import org.team2342.lib.motors.dumb.DumbMotorIOInputsAutoLogged; + +public class Kicker extends SubsystemBase { + private final DumbMotorIO kickerMotor; + + private final DumbMotorIOInputsAutoLogged kickerMotorInputs = new DumbMotorIOInputsAutoLogged(); + private final Alert kickerMotorAlert = + new Alert("Indexer Feeder Motor is diconnected", AlertType.kError); + + public Kicker(DumbMotorIO kickerMotor) { + this.kickerMotor = kickerMotor; + setName("Shooter/Kicker"); + setDefaultCommand(run(() -> kickerMotor.runVoltage(0.0))); + } + + @Override + public void periodic() { + kickerMotor.updateInputs(kickerMotorInputs); + + Logger.processInputs("Shooter/Kicker", kickerMotorInputs); + + kickerMotorAlert.set(!kickerMotorInputs.connected); + + ExecutionLogger.log("Shooter/Kicker"); + } + + public Command in() { + return run(() -> kickerMotor.runVoltage(KickerConstants.RUN_VOLTAGE)) + .withName("Kicker Motor Run"); + } + + public Command out() { + return run(() -> kickerMotor.runVoltage(-KickerConstants.RUN_VOLTAGE)) + .withName("Kicker Motor Run"); + } + + public Command stop() { + return runOnce( + () -> { + kickerMotor.runVoltage(0.0); + }) + .withName("Kicker Stop"); + } +} diff --git a/src/main/java/org/team2342/frc/subsystems/shooter/Flywheel.java b/src/main/java/org/team2342/frc/subsystems/shooter/Flywheel.java index 6f4d307..835b79d 100644 --- a/src/main/java/org/team2342/frc/subsystems/shooter/Flywheel.java +++ b/src/main/java/org/team2342/frc/subsystems/shooter/Flywheel.java @@ -6,10 +6,13 @@ package org.team2342.frc.subsystems.shooter; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import java.util.function.DoubleSupplier; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -25,9 +28,24 @@ public class Flywheel extends SubsystemBase { private final Alert motorAlert = new Alert("Flywheel motor is disconnected!", AlertType.kError); + private final SysIdRoutine sysId; + public Flywheel(SmartMotorIO motor) { this.motor = motor; + sysId = + new SysIdRoutine( + new SysIdRoutine.Config( + null, + null, + null, + (state) -> Logger.recordOutput("Shooter/Flywheel/SysIdState", state.toString())), + new SysIdRoutine.Mechanism( + (voltage) -> motor.runVoltage(voltage.in(Volts)), + (log) -> + Logger.recordOutput("Shooter/Flywheel/Voltage", motorInputs.appliedVolts[0]), + this)); + setName("Shooter/Flywheel"); setDefaultCommand(run(() -> motor.runVoltage(0.0))); } @@ -54,6 +72,14 @@ public void runVelocity(DoubleSupplier metersPerSec) { motor.runVelocity(radPerSec); } + private void warmUp(double idleSpeed) { + if (getVelocityMetersPerSec() > idleSpeed) { + motor.runVoltage(0.0); + } else { + runVelocity(idleSpeed); + } + } + public Command shoot(double metersPerSec) { return run(() -> runVelocity(metersPerSec)).withName("Run Shooter"); } @@ -62,10 +88,34 @@ public Command shoot(DoubleSupplier metersPerSec) { return run(() -> runVelocity(metersPerSec)).withName("Run Shooter"); } + public Command warmUp() { + return run(() -> warmUp(ShooterConstants.IDLE_SPEED)).withName("Warm Up Shooter"); + } + + public Command runVoltage(double volts) { + return run(() -> runVoltage(volts)).withName("Run Shooter Volts"); + } + public Command stop() { return runOnce(() -> motor.runVoltage(0.0)).withName("Shooter Stop"); } + /** Returns a command to run a quasistatic test in the specified direction. */ + public Command sysIdQuasistatic(SysIdRoutine.Direction direction) { + return run(() -> runVoltage(0.0)) + .withTimeout(1.0) + .andThen(sysId.quasistatic(direction)) + .withName("Flywheel Quasistatic"); + } + + /** Returns a command to run a dynamic test in the specified direction. */ + public Command sysIdDynamic(SysIdRoutine.Direction direction) { + return run(() -> runVoltage(0.0)) + .withTimeout(1.0) + .andThen(sysId.dynamic(direction)) + .withName("Flywheel Dynamic"); + } + @AutoLogOutput(key = "Shooter/Flywheel/VelocityMetersPerSec") public double getVelocityMetersPerSec() { return motorInputs.velocityRadPerSec * ShooterConstants.FLYWHEEL_RADIUS_METERS; diff --git a/src/main/java/org/team2342/frc/subsystems/shooter/Hood.java b/src/main/java/org/team2342/frc/subsystems/shooter/Hood.java index 2ce1d14..6b0e95d 100644 --- a/src/main/java/org/team2342/frc/subsystems/shooter/Hood.java +++ b/src/main/java/org/team2342/frc/subsystems/shooter/Hood.java @@ -69,6 +69,15 @@ public Command goToAngle(double targetAngle) { .withName("Hood GoToAngle"); } + public Command goToAngle(DoubleSupplier targetAngle) { + return run(() -> runAngle(targetAngle.getAsDouble())) + .until( + () -> + Math.abs(targetAngle.getAsDouble() - motorInputs.positionRad) + <= ShooterConstants.TARGET_TOLERANCE) + .withName("Hood GoToAngle"); + } + public Command holdAngle(double targetAngle) { return run(() -> runAngle(targetAngle)).withName("Hood HoldAngle"); } diff --git a/src/main/java/org/team2342/frc/subsystems/shooter/Turret.java b/src/main/java/org/team2342/frc/subsystems/shooter/Turret.java new file mode 100644 index 0000000..a130571 --- /dev/null +++ b/src/main/java/org/team2342/frc/subsystems/shooter/Turret.java @@ -0,0 +1,97 @@ +// Copyright (c) 2026 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.shooter; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.Alert; +import edu.wpi.first.wpilibj.Alert.AlertType; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; +import org.team2342.frc.Constants.TurretConstants; +import org.team2342.lib.logging.ExecutionLogger; +import org.team2342.lib.motors.smart.SmartMotorIO; +import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; + +public class Turret extends SubsystemBase { + + private final SmartMotorIO turretMotor; + private final SmartMotorIOInputsAutoLogged inputs = new SmartMotorIOInputsAutoLogged(); + private final Alert motorAlert = new Alert("Turret motor is disconnected!", AlertType.kError); + private double goal = TurretConstants.STARTING_ANGLE; + + public Turret(SmartMotorIO turretMotor) { + this.turretMotor = turretMotor; + setName("Shooter/Turret"); + setDefaultCommand(run(() -> turretMotor.runVoltage(0.0))); + } + + @Override + public void periodic() { + turretMotor.updateInputs(inputs); + Logger.processInputs("Shooter/Turret", inputs); + motorAlert.set(!inputs.motorsConnected[0]); + + ExecutionLogger.log("Shooter/Turret"); + } + + public void runPosition(Rotation2d target) { + this.goal = calculateTurretAngle(target); + turretMotor.runPosition(goal); + } + + public Command runPositionCommand(Rotation2d target) { + return run(() -> runPosition(target)).withName("Turret RunPosition"); + } + + public void goToPosition(Rotation2d target) { + this.goal = calculateTurretAngle(target); + turretMotor.runPosition(goal); + } + + public Command goToPositionCommand(Rotation2d target) { + return run(() -> goToPosition(target)) + .until(() -> Math.abs(inputs.positionRad - goal) <= TurretConstants.AT_POSITION_THRESHOLD) + .withName("Turret GoToPosition"); + } + + public Command runVoltage(double voltage) { + return run(() -> turretMotor.runVoltage(voltage)).withName("Turret Voltage"); + } + + public Command stop() { + return runOnce(() -> turretMotor.runVoltage(0.0)); + } + + @AutoLogOutput(key = "Shooter/Turret/Position") + public Rotation2d getTurretPosition() { + return Rotation2d.fromRadians(inputs.positionRad); + } + + public double getTurretVelocity() { + return inputs.velocityRadPerSec; + } + + @AutoLogOutput(key = "Shooter/Turret/Setpoint") + public Rotation2d getTurretSetpoint() { + return new Rotation2d(goal); + } + + public void zeroTurret() { + turretMotor.setPosition(0.0); + } + + private double calculateTurretAngle(Rotation2d angle) { + double calculatedAngle = MathUtil.inputModulus(angle.getRadians(), -Math.PI, Math.PI); + // if (calculatedAngle < 0) calculatedAngle += 2 * Math.PI; + // if (calculatedAngle > Math.PI * 2) calculatedAngle -= 2 * Math.PI; + return MathUtil.clamp( + calculatedAngle, TurretConstants.MIN_TURRET_ANGLE, TurretConstants.MAX_TURRET_ANGLE); + } +} 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 be01292..fbc086f 100644 --- a/src/main/java/org/team2342/frc/subsystems/vision/Vision.java +++ b/src/main/java/org/team2342/frc/subsystems/vision/Vision.java @@ -121,36 +121,38 @@ public void periodic() { || observation.pose().getY() < 0.0 || observation.pose().getY() > AllianceUtils.getFieldLayout().getFieldWidth(); - // Add pose to log - robotPoses.add(observation.pose()); - if (rejectPose) { - robotPosesRejected.add(observation.pose()); - // Skip if rejected - continue; - } else { - robotPosesAccepted.add(observation.pose()); + if (cameraIndex < 1) { + // Add pose to log + robotPoses.add(observation.pose()); + if (rejectPose) { + robotPosesRejected.add(observation.pose()); + // Skip if rejected + continue; + } else { + robotPosesAccepted.add(observation.pose()); + } + + // Calculate standard deviations + double stdDevFactor = + Math.pow(observation.averageTagDistance(), 2.0) / observation.tagCount(); + double linearStdDev = VisionConstants.LINEAR_STD_DEV_BASELINE * stdDevFactor; + double angularStdDev = VisionConstants.ANGULAR_STD_DEV_BASELINE * stdDevFactor; + if (observation.type() == PoseObservationType.MEGATAG_2 + || observation.type() == PoseObservationType.PHOTONVISION_CONSTRAINED) { + linearStdDev *= VisionConstants.LINEAR_STD_DEV_CONSTRAINED_FACTOR; + angularStdDev *= VisionConstants.ANGULAR_STD_DEV_CONSTRAINED_FACTOR; + } + if (cameraIndex < VisionConstants.CAMERA_STD_DEV_FACTORS.length) { + linearStdDev *= VisionConstants.CAMERA_STD_DEV_FACTORS[cameraIndex]; + angularStdDev *= VisionConstants.CAMERA_STD_DEV_FACTORS[cameraIndex]; + } + + // Send vision observation + consumer.accept( + observation.pose().toPose2d(), + observation.timestamp(), + VecBuilder.fill(linearStdDev, linearStdDev, angularStdDev)); } - - // Calculate standard deviations - double stdDevFactor = - Math.pow(observation.averageTagDistance(), 2.0) / observation.tagCount(); - double linearStdDev = VisionConstants.LINEAR_STD_DEV_BASELINE * stdDevFactor; - double angularStdDev = VisionConstants.ANGULAR_STD_DEV_BASELINE * stdDevFactor; - if (observation.type() == PoseObservationType.MEGATAG_2 - || observation.type() == PoseObservationType.PHOTONVISION_CONSTRAINED) { - linearStdDev *= VisionConstants.LINEAR_STD_DEV_CONSTRAINED_FACTOR; - angularStdDev *= VisionConstants.ANGULAR_STD_DEV_CONSTRAINED_FACTOR; - } - if (cameraIndex < VisionConstants.CAMERA_STD_DEV_FACTORS.length) { - linearStdDev *= VisionConstants.CAMERA_STD_DEV_FACTORS[cameraIndex]; - angularStdDev *= VisionConstants.CAMERA_STD_DEV_FACTORS[cameraIndex]; - } - - // Send vision observation - consumer.accept( - observation.pose().toPose2d(), - observation.timestamp(), - VecBuilder.fill(linearStdDev, linearStdDev, angularStdDev)); } // Log camera data diff --git a/src/main/java/org/team2342/frc/util/FiringSolver.java b/src/main/java/org/team2342/frc/util/FiringSolver.java new file mode 100644 index 0000000..ffd7eca --- /dev/null +++ b/src/main/java/org/team2342/frc/util/FiringSolver.java @@ -0,0 +1,115 @@ +// Copyright (c) 2026 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.util; + +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.Translation2d; +import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import org.littletonrobotics.junction.Logger; +import org.team2342.frc.Constants.TurretConstants; +import org.team2342.lib.util.AllianceUtils; + +public class FiringSolver { + private static FiringSolver instance; + + private static final int ITERATIONS = 5; + + public static final FiringSolution BUMPER_SHOT = new FiringSolution(new Rotation2d(), 23.5, 0.0); + + private FiringSolution lastSolution = null; + + private static final InterpolatingDoubleTreeMap angleMap = new InterpolatingDoubleTreeMap(); + private static final InterpolatingDoubleTreeMap speedMap = new InterpolatingDoubleTreeMap(); + private static final InterpolatingDoubleTreeMap tofMap = new InterpolatingDoubleTreeMap(); + + // TODO: tune real maps + static { + angleMap.put(1.859, 0.0); + angleMap.put(2.203, 0.0); + angleMap.put(2.510, 0.0); + angleMap.put(2.844, 0.0); + angleMap.put(3.046, 0.0); + angleMap.put(3.315, 0.0); + angleMap.put(3.973, 0.0); + angleMap.put(5.042, 0.0); + + speedMap.put(1.859, 23.0); + speedMap.put(2.203, 23.0); + speedMap.put(2.510, 25.0); + speedMap.put(2.844, 25.5); + speedMap.put(3.046, 26.0); + speedMap.put(3.315, 26.5); + speedMap.put(3.973, 28.5); + speedMap.put(5.042, 30.0); + + tofMap.put(1.859, 1.0); + } + + public static FiringSolver getInstance() { + if (instance == null) { + instance = new FiringSolver(); + } + return instance; + } + + public FiringSolution calculate(ChassisSpeeds velocity, Pose2d position) { + if (lastSolution != null) { + return lastSolution; + } + + Translation2d hub = + AllianceUtils.flipToAlliance(FieldConstants.Hub.topCenterPoint).toTranslation2d(); + Pose2d turretPose = + new Pose3d(position).transformBy(TurretConstants.TURRET_TRANSFORM).toPose2d(); + double robotAngle = position.getRotation().getRadians(); + + double velX = + velocity.vxMetersPerSecond + + velocity.omegaRadiansPerSecond + * (TurretConstants.TURRET_TRANSFORM.getY() * Math.cos(robotAngle) + - TurretConstants.TURRET_TRANSFORM.getX() * Math.sin(robotAngle)); + double velY = + velocity.vyMetersPerSecond + + velocity.omegaRadiansPerSecond + * (TurretConstants.TURRET_TRANSFORM.getX() * Math.cos(robotAngle) + - TurretConstants.TURRET_TRANSFORM.getY() * Math.sin(robotAngle)); + + double tof; + Pose2d predictedPose = turretPose; + + double predictedDistance = hub.getDistance(turretPose.getTranslation()); + for (int i = 0; i < ITERATIONS; i++) { + tof = tofMap.get(predictedDistance); + predictedPose = + new Pose2d( + turretPose.getTranslation().plus(new Translation2d(velX * tof, velY * tof)), + turretPose.getRotation()); + predictedDistance = hub.getDistance(predictedPose.getTranslation()); + } + Logger.recordOutput("FiringSolver/PredictedPose", predictedPose); + Logger.recordOutput("FiringSolver/PredictedDistance", predictedDistance); + + Rotation2d turretAngle = hub.minus(predictedPose.getTranslation()).getAngle(); + turretAngle = turretAngle.minus(position.getRotation()).minus(Rotation2d.k180deg); + + double hoodAngle = angleMap.get(predictedDistance); + double wheelSpeed = speedMap.get(predictedDistance); + + lastSolution = new FiringSolution(turretAngle, wheelSpeed, hoodAngle); + + return lastSolution; + } + + public void clearCachedSolution() { + lastSolution = null; + } + + public record FiringSolution(Rotation2d turretAngle, double wheelSpeed, double hoodAngle) {} +} From 5109f2bd791207b6a2a22edc4febe4d057196af5 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Tue, 10 Mar 2026 19:29:51 -0400 Subject: [PATCH 11/15] updating code --- src/main/java/org/team2342/frc/Constants.java | 18 ++++++ src/main/java/org/team2342/frc/Robot.java | 4 +- .../java/org/team2342/frc/RobotContainer.java | 7 +-- .../team2342/frc/subsystems/intake/Pivot.java | 60 ++++++++----------- 4 files changed, 47 insertions(+), 42 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index f2590b9..e65fe9c 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -198,6 +198,24 @@ public static final class IntakeConstants { new DCMotorSim( LinearSystemId.createDCMotorSystem(INTAKE_WHEELS_SIM_MOTOR, 0.003, 1), INTAKE_WHEELS_SIM_MOTOR); + + public static final double PIVOT_GEAR_RATIO = 1.0; + public static final double MIN_INTAKE_ANGLE = -1.0; + public static final double MAX_INTAKE_ANGLE = 1.0; + + public static final PIDFFConfigs PIVOT_MOTOR_PID_CONFIGS = + new PIDFFConfigs().withKP(10).withKI(0).withKD(0); + public static final SmartMotorConfig PIVOT_MOTOR_CONFIG = + new SmartMotorConfig() + .withGearRatio(PIVOT_GEAR_RATIO) + .withControlType(ControlType.PROFILED_POSITION) + .withIdleMode(IdleMode.BRAKE) + .withSupplyCurrentLimit(30.0) + .withFeedbackConfig( + FeedbackConfig.fused(CANConstants.INTAKE_PIVOT_ENCODER_ID, 1.0, 0.0, false)) + .withProfileConstraintsRad( + new TrapezoidProfile.Constraints( + Units.degreesToRadians(1800), Math.PI)); } public static final class ShooterConstants { diff --git a/src/main/java/org/team2342/frc/Robot.java b/src/main/java/org/team2342/frc/Robot.java index b92fac6..0bafef0 100644 --- a/src/main/java/org/team2342/frc/Robot.java +++ b/src/main/java/org/team2342/frc/Robot.java @@ -171,9 +171,7 @@ public void disabledInit() {} public void disabledPeriodic() {} @Override - public void disabledExit() { - CommandScheduler.getInstance().schedule(robotContainer.getPivot().out()); - } + 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 a0b5475..d702636 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -56,7 +56,6 @@ import org.team2342.frc.util.FiringSolver; import org.team2342.lib.motors.dumb.DumbMotorIO; import org.team2342.lib.motors.dumb.DumbMotorIOSim; -import org.team2342.lib.motors.dumb.DumbMotorIOTalonFX; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOSim; import org.team2342.lib.motors.smart.SmartMotorIOTalonFX; @@ -128,7 +127,7 @@ public RobotContainer() { wheels = new Wheels(new DumbMotorIO() {}); pivot = new Pivot( - new DumbMotorIOTalonFX( + new SmartMotorIOTalonFX( CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); hood = new Hood(new SmartMotorIO() {}); @@ -185,7 +184,7 @@ public RobotContainer() { ShooterConstants.HOOD_SIM, 1)); turret = new Turret(new SmartMotorIO() {}); - pivot = new Pivot(new DumbMotorIO() {}); + pivot = new Pivot(new SmartMotorIO() {}); break; @@ -205,7 +204,7 @@ public RobotContainer() { new VisionIO() {}); indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}); wheels = new Wheels(new DumbMotorIO() {}); - pivot = new Pivot(new DumbMotorIO() {}); + pivot = new Pivot(new SmartMotorIO() {}); flywheel = new Flywheel(new SmartMotorIO() {}); hood = new Hood(new SmartMotorIO() {}); turret = new Turret(new SmartMotorIO() {}); diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 3c51d80..5754ac8 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -10,22 +10,26 @@ import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; import org.team2342.frc.Constants.PivotConstants; import org.team2342.lib.logging.ExecutionLogger; -import org.team2342.lib.motors.dumb.DumbMotorIO; -import org.team2342.lib.motors.dumb.DumbMotorIOInputsAutoLogged; +import org.team2342.lib.motors.smart.SmartMotorIO; +import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; public class Pivot extends SubsystemBase { - private final DumbMotorIO pivotMotor; - private final DumbMotorIOInputsAutoLogged pivotMotorInputs = new DumbMotorIOInputsAutoLogged(); + private final SmartMotorIO pivotMotor; + private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); + + @AutoLogOutput(key = "Intake/Pivot/TargetAngle") + private double goal = 0.0; private final Alert pivotMotorAlert = new Alert("Pivot motor is disconnected!", AlertType.kError); - public Pivot(DumbMotorIO pivotMotor) { + public Pivot(SmartMotorIO pivotMotor) { this.pivotMotor = pivotMotor; - setName("Pivot"); + setName("Intake/Pivot"); setDefaultCommand(run(() -> pivotMotor.runVoltage(0.0))); } @@ -33,44 +37,30 @@ public Pivot(DumbMotorIO pivotMotor) { public void periodic() { pivotMotor.updateInputs(pivotMotorInputs); Logger.processInputs("Intake/Pivot", pivotMotorInputs); - Logger.processInputs("Shooter/Hood/Motor", pivotMotorInputs); - + pivotMotorAlert.set(!pivotMotorInputs.motorsConnected[0]); ExecutionLogger.log("Intake/Pivot"); } - // @AutoLogOutput(key = "Intake/Pivot/Angle") - // public Rotation2d getAngle() { - // return Rotation2d.fromRadians(pivotMotorInputs.positionRad); - // } + public void runAngle(double angle) { + goal = angle; + pivotMotor.runPosition(angle); + } - // public Command goToAngle(Rotation2d targetAngle) { - // return run(() -> pivotMotor.runPosition(targetAngle.getRadians())) - // .until( - // () -> { - // // Using minus() and getRadians() handles the wrap-around math for you! - // double error = targetAngle.minus(getAngle()).getRadians(); - // return Math.abs(error) < PivotConstants.AT_TARGET_TOLERANCE; - // }) - // .withName("Pivot Go To Angle"); // Fixed the quote here - // } + public Command goToAngle(double angle) { + return run(() -> runAngle(angle)) + .until(() -> Math.abs(goal - angle) <= PivotConstants.AT_TARGET_TOLERANCE) + .withName("Pivot Go To Angle"); + } - public Command in() { - return run(() -> pivotMotor.runVoltage(PivotConstants.IN_VOLTAGE)) - .withTimeout(2.0) - .withName("Pivot In"); + public Command runVoltage(double voltage) { + return run(() -> pivotMotor.runVoltage(voltage)).withName("Pivot Run Voltage"); } - public Command out() { - return run(() -> pivotMotor.runVoltage(-PivotConstants.IN_VOLTAGE)) - .withTimeout(2.0) - .withName("Pivot Out"); + public Command holdAngle(double angle) { + return run(() -> runAngle(angle)).withName("Pivot Hold Angle"); } - // public Command holdAngle(Rotation2d targetAngle) { - // return run(() -> pivotMotor.runPosition(targetAngle.getRadians())).withName("Pivot Hold - // Angle"); - // } public Command stop() { - return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Stop Pivot"); + return runOnce(() -> pivotMotor.runVoltage(0.0)).withName("Pivot Stop"); } } From 741b13ee92f7d2766c2d9cdf4971af16e5ac6c7c Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Tue, 10 Mar 2026 21:29:27 -0400 Subject: [PATCH 12/15] encoder wip --- src/main/java/org/team2342/frc/Constants.java | 36 ++++--------------- .../java/org/team2342/frc/RobotContainer.java | 10 ++---- .../team2342/frc/subsystems/intake/Pivot.java | 3 +- 3 files changed, 10 insertions(+), 39 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index e65fe9c..692b748 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -199,8 +199,8 @@ public static final class IntakeConstants { LinearSystemId.createDCMotorSystem(INTAKE_WHEELS_SIM_MOTOR, 0.003, 1), INTAKE_WHEELS_SIM_MOTOR); - public static final double PIVOT_GEAR_RATIO = 1.0; - public static final double MIN_INTAKE_ANGLE = -1.0; + public static final double PIVOT_GEAR_RATIO = 40; + public static final double MIN_INTAKE_ANGLE = 0.0; public static final double MAX_INTAKE_ANGLE = 1.0; public static final PIDFFConfigs PIVOT_MOTOR_PID_CONFIGS = @@ -212,10 +212,9 @@ public static final class IntakeConstants { .withIdleMode(IdleMode.BRAKE) .withSupplyCurrentLimit(30.0) .withFeedbackConfig( - FeedbackConfig.fused(CANConstants.INTAKE_PIVOT_ENCODER_ID, 1.0, 0.0, false)) + FeedbackConfig.fused(CANConstants.INTAKE_PIVOT_ENCODER_ID, 1.0, -0.176 / 2, false)) .withProfileConstraintsRad( - new TrapezoidProfile.Constraints( - Units.degreesToRadians(1800), Math.PI)); + new TrapezoidProfile.Constraints(Units.degreesToRadians(1800), Math.PI)); } public static final class ShooterConstants { @@ -318,9 +317,9 @@ public static final class CANConstants { public static final int HOOD_MOTOR_ID = 15; public static final int HOOD_ENCODER_ID = 16; - public static final int INTAKE_WHEEL_MOTOR_ID = 17; - public static final int INTAKE_PIVOT_MOTOR_ID = 18; - public static final int INTAKE_PIVOT_ENCODER_ID = 19; + public static final int INTAKE_WHEEL_MOTOR_ID = 18; + public static final int INTAKE_PIVOT_MOTOR_ID = 19; + public static final int INTAKE_PIVOT_ENCODER_ID = 20; public static final int INDEXER_WHEEL_ID = 20; public static final int INDEXER_BELT_ID = 21; @@ -331,25 +330,4 @@ public static final class CANConstants { public static final int PDH_ID = 62; } - - public static final class PivotConstants { - public static final double GEAR_RATIO = 27; - public static final double CLAW_LENGTH = Units.inchesToMeters(16.6); - public static final double MIN_ANGLE = -0.93; - public static final double MAX_ANGLE = 1.43; - public static final double CUTOFF_ANGLE = 1.2; - public static final double MOVE_ANGLE = 0.5; - public static final double AT_TARGET_TOLERANCE = 0.01; - public static final double IN_VOLTAGE = 5.0; - - public static final SmartMotorConfig PIVOT_CONFIG = - new SmartMotorConfig() - .withGearRatio(GEAR_RATIO) - .withIdleMode(IdleMode.BRAKE) - .withProfileConstraintsRad( - new TrapezoidProfile.Constraints( - Units.degreesToRadians(1260), Units.degreesToRadians(1080))) - .withControlType(ControlType.PROFILED_POSITION) - .withSupplyCurrentLimit(40); - } } diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index d702636..0d8bb5d 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -28,7 +28,6 @@ import org.team2342.frc.Constants.DriveConstants; import org.team2342.frc.Constants.IndexerConstants; import org.team2342.frc.Constants.IntakeConstants; -import org.team2342.frc.Constants.PivotConstants; import org.team2342.frc.Constants.ShooterConstants; import org.team2342.frc.Constants.TurretConstants; import org.team2342.frc.Constants.VisionConstants; @@ -116,19 +115,14 @@ public RobotContainer() { new SmartMotorIOTalonFX( CANConstants.TURRET_ID, TurretConstants.TURRET_CONFIG.withPIDFFConfigs(TurretConstants.PID_CONFIG))); - flywheel = - new Flywheel( - new SmartMotorIOTalonFX( - CANConstants.FLYWHEEL_MOTOR_ID, - ShooterConstants.FLYWHEEL_CONFIG.withPIDFFConfigs( - ShooterConstants.FLYWHEEL_PID_CONFIGS))); + flywheel = new Flywheel(new SmartMotorIO() {}); indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}); wheels = new Wheels(new DumbMotorIO() {}); pivot = new Pivot( new SmartMotorIOTalonFX( - CANConstants.INTAKE_PIVOT_MOTOR_ID, PivotConstants.PIVOT_CONFIG)); + CANConstants.INTAKE_PIVOT_MOTOR_ID, IntakeConstants.PIVOT_MOTOR_CONFIG)); hood = new Hood(new SmartMotorIO() {}); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 5754ac8..901efc1 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -12,7 +12,6 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import org.team2342.frc.Constants.PivotConstants; import org.team2342.lib.logging.ExecutionLogger; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; @@ -48,7 +47,7 @@ public void runAngle(double angle) { public Command goToAngle(double angle) { return run(() -> runAngle(angle)) - .until(() -> Math.abs(goal - angle) <= PivotConstants.AT_TARGET_TOLERANCE) + .until(() -> Math.abs(goal - angle) <= 0.01) .withName("Pivot Go To Angle"); } From d42abe8672ead8c9ac4836653cc197b17b8fd9f6 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Wed, 11 Mar 2026 19:56:24 -0400 Subject: [PATCH 13/15] wip --- src/main/java/org/team2342/frc/Constants.java | 10 ++++++---- src/main/java/org/team2342/frc/RobotContainer.java | 3 ++- .../java/org/team2342/frc/subsystems/intake/Pivot.java | 2 +- src/main/java/org/team2342/lib | 2 +- 4 files changed, 10 insertions(+), 7 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index 692b748..e853696 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -201,18 +201,20 @@ public static final class IntakeConstants { public static final double PIVOT_GEAR_RATIO = 40; public static final double MIN_INTAKE_ANGLE = 0.0; - public static final double MAX_INTAKE_ANGLE = 1.0; + public static final double MAX_INTAKE_ANGLE = 2.23; public static final PIDFFConfigs PIVOT_MOTOR_PID_CONFIGS = - new PIDFFConfigs().withKP(10).withKI(0).withKD(0); + new PIDFFConfigs().withKP(100).withKI(0).withKD(0); public static final SmartMotorConfig PIVOT_MOTOR_CONFIG = new SmartMotorConfig() - .withGearRatio(PIVOT_GEAR_RATIO) + .withGearRatio(1.0) .withControlType(ControlType.PROFILED_POSITION) .withIdleMode(IdleMode.BRAKE) + .withMotorInverted(false) .withSupplyCurrentLimit(30.0) .withFeedbackConfig( - FeedbackConfig.fused(CANConstants.INTAKE_PIVOT_ENCODER_ID, 1.0, -0.176 / 2, false)) + FeedbackConfig.fused( + CANConstants.INTAKE_PIVOT_ENCODER_ID, PIVOT_GEAR_RATIO, 0.173, true)) .withProfileConstraintsRad( new TrapezoidProfile.Constraints(Units.degreesToRadians(1800), Math.PI)); } diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 0d8bb5d..4249d73 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -316,7 +316,8 @@ private void configureBindings() { drive) .ignoringDisable(true)); - driverController.leftTrigger().whileTrue(wheels.in()).onFalse(wheels.stop()); + driverController.leftTrigger().whileTrue(pivot.holdAngle(0.0)).onFalse(pivot.stop()); + driverController.leftBumper().whileTrue(pivot.holdAngle(1.0)).onFalse(pivot.stop()); // Shooting Controls driverController diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index 901efc1..e5aaed2 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -22,7 +22,7 @@ public class Pivot extends SubsystemBase { private final SmartMotorIOInputsAutoLogged pivotMotorInputs = new SmartMotorIOInputsAutoLogged(); @AutoLogOutput(key = "Intake/Pivot/TargetAngle") - private double goal = 0.0; + private double goal = 2.23; private final Alert pivotMotorAlert = new Alert("Pivot motor is disconnected!", AlertType.kError); diff --git a/src/main/java/org/team2342/lib b/src/main/java/org/team2342/lib index ce2bd1b..6c362e3 160000 --- a/src/main/java/org/team2342/lib +++ b/src/main/java/org/team2342/lib @@ -1 +1 @@ -Subproject commit ce2bd1b8fb600eda5913573d090f162321ee3367 +Subproject commit 6c362e39189b227918ae923db2404b37c2f5c8a1 From c6c982184fd1c30d536eb8455d82b95d5ed50918 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Wed, 11 Mar 2026 20:07:22 -0400 Subject: [PATCH 14/15] tuned --- src/main/java/org/team2342/frc/Constants.java | 11 ++++++----- src/main/java/org/team2342/frc/RobotContainer.java | 4 +++- .../org/team2342/frc/subsystems/intake/Pivot.java | 6 ++++-- 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/src/main/java/org/team2342/frc/Constants.java b/src/main/java/org/team2342/frc/Constants.java index e853696..6d83b54 100644 --- a/src/main/java/org/team2342/frc/Constants.java +++ b/src/main/java/org/team2342/frc/Constants.java @@ -200,23 +200,24 @@ public static final class IntakeConstants { INTAKE_WHEELS_SIM_MOTOR); public static final double PIVOT_GEAR_RATIO = 40; - public static final double MIN_INTAKE_ANGLE = 0.0; - public static final double MAX_INTAKE_ANGLE = 2.23; + public static final double MIN_ANGLE = 0.1; + public static final double MAX_ANGLE = 2.23; public static final PIDFFConfigs PIVOT_MOTOR_PID_CONFIGS = - new PIDFFConfigs().withKP(100).withKI(0).withKD(0); + new PIDFFConfigs().withKP(45).withKI(15).withKD(7); public static final SmartMotorConfig PIVOT_MOTOR_CONFIG = new SmartMotorConfig() .withGearRatio(1.0) .withControlType(ControlType.PROFILED_POSITION) .withIdleMode(IdleMode.BRAKE) .withMotorInverted(false) - .withSupplyCurrentLimit(30.0) + .withSupplyCurrentLimit(40.0) .withFeedbackConfig( FeedbackConfig.fused( CANConstants.INTAKE_PIVOT_ENCODER_ID, PIVOT_GEAR_RATIO, 0.173, true)) .withProfileConstraintsRad( - new TrapezoidProfile.Constraints(Units.degreesToRadians(1800), Math.PI)); + new TrapezoidProfile.Constraints( + Units.degreesToRadians(1800), Units.degreesToRadians(540))); } public static final class ShooterConstants { diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index 4249d73..cf6a35e 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -122,7 +122,9 @@ public RobotContainer() { pivot = new Pivot( new SmartMotorIOTalonFX( - CANConstants.INTAKE_PIVOT_MOTOR_ID, IntakeConstants.PIVOT_MOTOR_CONFIG)); + CANConstants.INTAKE_PIVOT_MOTOR_ID, + IntakeConstants.PIVOT_MOTOR_CONFIG.withPIDFFConfigs( + IntakeConstants.PIVOT_MOTOR_PID_CONFIGS))); hood = new Hood(new SmartMotorIO() {}); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); diff --git a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java index e5aaed2..9dbc222 100644 --- a/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java +++ b/src/main/java/org/team2342/frc/subsystems/intake/Pivot.java @@ -6,12 +6,14 @@ package org.team2342.frc.subsystems.intake; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import org.team2342.frc.Constants.IntakeConstants; import org.team2342.lib.logging.ExecutionLogger; import org.team2342.lib.motors.smart.SmartMotorIO; import org.team2342.lib.motors.smart.SmartMotorIOInputsAutoLogged; @@ -41,8 +43,8 @@ public void periodic() { } public void runAngle(double angle) { - goal = angle; - pivotMotor.runPosition(angle); + goal = MathUtil.clamp(angle, IntakeConstants.MIN_ANGLE, IntakeConstants.MAX_ANGLE); + pivotMotor.runPosition(goal); } public Command goToAngle(double angle) { From 360c9c34d96a35718b948cabedc2ab73b3f35ee5 Mon Sep 17 00:00:00 2001 From: Luddo183 <93882319+Luddo183@users.noreply.github.com> Date: Wed, 11 Mar 2026 20:12:33 -0400 Subject: [PATCH 15/15] fix --- src/main/java/org/team2342/frc/RobotContainer.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/org/team2342/frc/RobotContainer.java b/src/main/java/org/team2342/frc/RobotContainer.java index f6e3510..b8a06d7 100644 --- a/src/main/java/org/team2342/frc/RobotContainer.java +++ b/src/main/java/org/team2342/frc/RobotContainer.java @@ -116,7 +116,7 @@ public RobotContainer() { CANConstants.TURRET_ID, TurretConstants.TURRET_CONFIG.withPIDFFConfigs(TurretConstants.PID_CONFIG))); flywheel = new Flywheel(new SmartMotorIO() {}); - + hood = new Hood(new SmartMotorIO() {}); indexer = new Indexer(new DumbMotorIO() {}, new DumbMotorIO() {}); wheels = new Wheels(new DumbMotorIO() {}); pivot = @@ -127,7 +127,7 @@ public RobotContainer() { IntakeConstants.PIVOT_MOTOR_PID_CONFIGS))); new SmartMotorIOTalonFX( CANConstants.TURRET_ID, - TurretConstants.TURRET_CONFIG.withPIDFFConfigs(TurretConstants.PID_CONFIG))); + TurretConstants.TURRET_CONFIG.withPIDFFConfigs(TurretConstants.PID_CONFIG)); LoggedPowerDistribution.getInstance(CANConstants.PDH_ID, ModuleType.kRev); break;