diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 033c72d..ec57630 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -4,6 +4,14 @@ package frc.robot; +import org.photonvision.SimVisionTarget; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.util.Units; + /** * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean * constants. This class should not be used for any other purpose. All constants should be declared @@ -12,4 +20,40 @@ *

It is advised to statically import this class (or one of its inner classes) wherever the * constants are needed, to reduce verbosity. */ -public final class Constants {} +public final class Constants { + public static final class Vision{ + // public static final double targetWidth = + + // Units.inchesToMeters(91.0) - Units.inchesToMeters(6.70); // meters + + // // See + + // // https://firstfrc.blob.core.windows.net/frc2020/PlayingField/2020FieldDrawing-SeasonSpecific.pdf + + // // page 197 + + public static final double targetHeight = + + Units.inchesToMeters(91.0); // meters + + public static final double targetHeightAboveGround = Units.inchesToMeters(81.19); // meters + + // See + // https://firstfrc.blob.core.windows.net/frc2020/PlayingField/LayoutandMarkingDiagram.pdf + + // pages 4 and 5 + + public static final double kFarTgtXPos = 1.0; + + public static final String kCamName = "targetCam"; + public static final Translation2d translation = new Translation2d(.5, 0); + public static final Rotation2d rotation = new Rotation2d(0.0); + public static final Transform2d kCameraToRobot = new Transform2d(translation, rotation); + } + + public static final double kTurnRateToleranceDegPerS = 10; + public static final double kTurnToleranceDeg = 10; + public static final double kTurnP = 0.01; + public static final double kTurnI = 0; + public static final double kTurnD = 0.0001; +} diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index af0de7b..2e2c855 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,9 +4,19 @@ package frc.robot; +import javax.tools.Diagnostic; + import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.commands.AimToBall; +import frc.robot.commands.AimToBallManualDist; +import frc.robot.commands.AimToTarget; +import frc.robot.commands.AutoCommand; +import frc.robot.commands.TurnToAngle; import frc.robot.subsystems.DriveSystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.RunCommand; @@ -22,15 +32,18 @@ public class RobotContainer { // The robot's subsystems and commands are defined here... private final DriveSystem robotDrive = new DriveSystem(); private JoystickButton left_bumper; - private GenericHID driveController = new XboxController(0) ; + private JoystickButton right_bumper; + private JoystickButton a_button; + private GenericHID driveController = new XboxController(0) ; /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { configureButtonBindings(); + robotDrive.resetGyro(); robotDrive.setDefaultCommand( - + (new RunCommand( () -> robotDrive.drive( @@ -51,10 +64,14 @@ public RobotContainer() { * edu.wpi.first.wpilibj2.command.button.JoystickButton}. */ private void configureButtonBindings() { - left_bumper = new JoystickButton(driveController, XboxController.Button.kY.value); + left_bumper = new JoystickButton(driveController, XboxController.Button.kLeftBumper.value); + right_bumper = new JoystickButton(driveController, XboxController.Button.kRightBumper.value); + a_button = new JoystickButton(driveController, XboxController.Button.kA.value); - left_bumper.whileHeld(new AimToBall(robotDrive)); + left_bumper.whileHeld(new AimToTarget(robotDrive)); + right_bumper.whileHeld(new AimToBall(robotDrive)); + a_button.whenPressed(new AutoCommand(robotDrive)); } /** diff --git a/src/main/java/frc/robot/commands/AimToBall.java b/src/main/java/frc/robot/commands/AimToBall.java index 602f113..10142bf 100644 --- a/src/main/java/frc/robot/commands/AimToBall.java +++ b/src/main/java/frc/robot/commands/AimToBall.java @@ -11,6 +11,11 @@ import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.CommandBase; import frc.robot.subsystems.DriveSystem; @@ -18,19 +23,21 @@ public class AimToBall extends CommandBase { private DriveSystem m_subsystem; private boolean m_finished = false; - final double LINEAR_P = 0.1; + final double LINEAR_P = 0.25; final double LINEAR_D = 0.0; PIDController forwardController = new PIDController(LINEAR_P, 0, LINEAR_D); - final double ANGULAR_P = 0.1; + final double ANGULAR_P = 0.8;// SmartDashboard.getNumber("Angular Pos", 0.1); - final double ANGULAR_D = -.1; + final double ANGULAR_D = 0.01; PIDController turnController = new PIDController(ANGULAR_P, 0, ANGULAR_D); private NetworkTable table; + private boolean isBlue; + /** * Creates a new ExampleCommand. * @@ -39,36 +46,55 @@ public class AimToBall extends CommandBase { public AimToBall(DriveSystem subsystem) { m_subsystem = subsystem; m_finished = true; + // Use addRequirements() here to declare subsystem dependencies. addRequirements(subsystem); } @Override public void initialize() { + System.out.println("Aiming to Ball"); NetworkTableInstance inst = NetworkTableInstance.getDefault(); table = inst.getTable("ML"); } + @Override + public boolean isFinished(){ + return m_finished; + } + // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { + isBlue = DriverStation.getAlliance() == DriverStation.Alliance.Blue; m_finished = false; - NetworkTableEntry xEntry = table.getEntry("best_blue_x"); + NetworkTableEntry xEntry = table.getEntry(isBlue ? "best_blue_x" : "best_red_x"); + NetworkTableEntry sizeEntry = table.getEntry(isBlue ? "best_blue_size" : "best_red_size"); System.out.println(xEntry); NetworkTableEntry widthEntry = table.getEntry("width"); + double turnSpeed = 0.0; + double linearSpeed = 0.0; if ((Double) xEntry.getNumber(Double.valueOf(0.0)) > Double.valueOf(1.0)) { Double width = (Double) widthEntry.getNumber(Double.valueOf(0)); Double best_target_x = (Double) xEntry.getNumber(0); System.out.println(best_target_x); - double error = best_target_x - width / 2.0; - if (Math.abs(error) > 50) { - System.out.println(error); + double errorAng = best_target_x - width / 2.0; + m_finished = errorAng < 10; + if (Math.abs(errorAng) > 5) { + // System.out.println(errorAng); // error = error / 160.0; - double turnSpeed = turnController.calculate(error, 0); - System.out.println(turnSpeed); - m_subsystem.drive(0.0, turnSpeed * .04); + turnSpeed = turnController.calculate(errorAng, 0); + turnSpeed = turnSpeed * (1.0 / 160.0) * 0.5; + SmartDashboard.putNumber("turnSpeed", turnSpeed); + } + } + if ((Double) sizeEntry.getNumber(Double.valueOf(0.0)) > Double.valueOf(1.0)) { + Double size = (Double) sizeEntry.getNumber(Double.valueOf(0)); + if(Math.abs(size-28000) > 1500){ + double errorLin = size - 28000; + linearSpeed = forwardController.calculate(errorLin/4000.0, 0.0); } - } + m_subsystem.drive(linearSpeed, turnSpeed); } } \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/AimToBallManualDist.java b/src/main/java/frc/robot/commands/AimToBallManualDist.java new file mode 100644 index 0000000..787f337 --- /dev/null +++ b/src/main/java/frc/robot/commands/AimToBallManualDist.java @@ -0,0 +1,120 @@ +package frc.robot.commands; + +import java.util.Iterator; + +import com.fasterxml.jackson.core.JsonProcessingException; +import com.fasterxml.jackson.databind.JsonNode; +import com.fasterxml.jackson.databind.ObjectMapper; +import com.fasterxml.jackson.databind.node.ArrayNode; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEntry; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.DriveSystem; + +public class AimToBallManualDist extends CommandBase { + private DriveSystem m_subsystem; + private boolean m_finished = false; + + final double LINEAR_P = 0.1; + + final double LINEAR_D = 0.0; + + PIDController forwardController = new PIDController(LINEAR_P, 0, LINEAR_D); + + final double ANGULAR_P = 0.8;// SmartDashboard.getNumber("Angular Pos", 0.1); + + final double ANGULAR_D = 0.01; + + PIDController turnController = new PIDController(ANGULAR_P, 0, ANGULAR_D); + private NetworkTable table; + + GenericHID controller; + + private Boolean isBlue; + + public AimToBallManualDist(DriveSystem subsystem, GenericHID driveController) { + m_subsystem = subsystem; + m_finished = true; + controller = driveController; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + public AimToBallManualDist(DriveSystem subsystem) { + m_subsystem = subsystem; + m_finished = true; + controller = null; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + public AimToBallManualDist(DriveSystem subsystem, GenericHID driveController, Boolean isTeamBlue) { + m_subsystem = subsystem; + m_finished = true; + controller = driveController; + isBlue = isTeamBlue; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + public AimToBallManualDist(DriveSystem subsystem, Boolean isTeamBlue) { + m_subsystem = subsystem; + m_finished = true; + controller = null; + isBlue = isTeamBlue; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + + @Override + public void initialize() { + System.out.println("Aiming to Ball"); + NetworkTableInstance inst = NetworkTableInstance.getDefault(); + table = inst.getTable("ML"); + } + + @Override + public boolean isFinished(){ + return m_finished; + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + m_finished = false; + NetworkTableEntry xEntry = table.getEntry(isBlue ? "best_blue_x": "best_red_x"); + System.out.println(xEntry); + NetworkTableEntry widthEntry = table.getEntry("width"); + if ((Double) xEntry.getNumber(Double.valueOf(0.0)) > Double.valueOf(1.0)) { + Double width = (Double) widthEntry.getNumber(Double.valueOf(0)); + Double best_target_x = (Double) xEntry.getNumber(0); + System.out.println(best_target_x); + double error = best_target_x - width / 2.0; + m_finished = error < 10; + if (Math.abs(error) > 5) { + System.out.println(error); + // error = error / 160.0; + double turnSpeed = turnController.calculate(error, 0); + turnSpeed = turnSpeed * (1.0 / 160.0) * 0.5; + SmartDashboard.putNumber("turnSpeed", turnSpeed); + if (controller != null) { + m_subsystem.drive(controller.getRawAxis(1) > 0.1 || controller.getRawAxis(1) < -0.1 + ? -controller.getRawAxis(1) + : 0.0, turnSpeed); + + } else { + m_subsystem.drive(0.0, turnSpeed); + } + } + + } + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/AimToTarget.java b/src/main/java/frc/robot/commands/AimToTarget.java new file mode 100644 index 0000000..af7b705 --- /dev/null +++ b/src/main/java/frc/robot/commands/AimToTarget.java @@ -0,0 +1,109 @@ +package frc.robot.commands; + +import org.photonvision.PhotonUtils; +import org.photonvision.targeting.PhotonPipelineResult; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants; +import frc.robot.subsystems.DriveSystem; + +public class AimToTarget extends CommandBase{ + private DriveSystem m_subsystem; + private boolean m_finished = false; + + final double LINEAR_P = 0.7; + final double LINEAR_D = 0; + PIDController forwardController = new PIDController(LINEAR_P, 0, LINEAR_D); + + final double ANGULAR_P = 0.7; + final double ANGULAR_D = 0; + PIDController turnController = new PIDController(ANGULAR_P, 0, ANGULAR_D); + double targetRange = Constants.Vision.kFarTgtXPos; + + /** + * Creates a new ExampleCommand. + * + * @param subsystem The subsystem used by this command. + */ + public AimToTarget(DriveSystem subsystem) { + m_subsystem = subsystem; + m_finished = true; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + public AimToTarget(DriveSystem subsystem, double i) { + m_subsystem = subsystem; + m_finished = true; + targetRange =i; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(subsystem); + } + + @Override + public void initialize(){ + + System.out.println("Aiming To Target"); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + m_finished = false; + + PhotonPipelineResult result = m_subsystem.getCamera().getLatestResult(); + + if (result.hasTargets()) { + + // First calculate range + + double range = + + PhotonUtils.calculateDistanceToTargetMeters( + + Units.inchesToMeters(6.70), + + Constants.Vision.targetHeight, + + Units.degreesToRadians(45), + + Units.degreesToRadians(result.getBestTarget().getPitch())); + + // Use this range as the measurement we give to the PID controller. + + // -1.0 required to ensure positive PID controller effort _increases_ range + + double forwardSpeed = forwardController.calculate(range, targetRange); + double errorForward = Math.abs(range) - targetRange; + // Also calculate angular power + + // -1.0 required to ensure positive PID controller effort _increases_ yaw + + double turnSpeed = turnController.calculate(result.getBestTarget().getYaw(), 0); + double errorTurn = Math.abs(result.getBestTarget().getYaw()); + SmartDashboard.putNumber("ef", errorForward); + SmartDashboard.putNumber("forwardSpeed",forwardSpeed); + SmartDashboard.putNumber("range", range); + + if(Math.abs(errorForward) > 0.15 || errorTurn > 5){ + m_subsystem.drive(forwardSpeed*-1.0, turnSpeed/15.0); + } + else{ + m_finished = true; + } + + } else { + + m_finished = true; + } + + // Use our forward/turn speeds to control the drivetrain + } + @Override + public boolean isFinished(){ + return m_finished; + } +} diff --git a/src/main/java/frc/robot/commands/AutoCommand.java b/src/main/java/frc/robot/commands/AutoCommand.java new file mode 100644 index 0000000..e95f573 --- /dev/null +++ b/src/main/java/frc/robot/commands/AutoCommand.java @@ -0,0 +1,18 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; +import frc.robot.subsystems.DriveSystem; + +public class AutoCommand extends SequentialCommandGroup { + public AutoCommand(DriveSystem drive) { + addCommands( + // Drive forward the specified distance + new AimToTarget(drive,1), + new AimToTarget(drive,1.5), + new TurnToAngle(135, drive), + new AimToBall(drive), + new TurnToAngle(0,drive), + new AimToTarget(drive,1) + ); + } +} diff --git a/src/main/java/frc/robot/commands/TurnToAngle.java b/src/main/java/frc/robot/commands/TurnToAngle.java new file mode 100644 index 0000000..37e121d --- /dev/null +++ b/src/main/java/frc/robot/commands/TurnToAngle.java @@ -0,0 +1,49 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import frc.robot.Constants; +import frc.robot.subsystems.DriveSystem; +import edu.wpi.first.wpilibj2.command.PIDCommand; + +/** A command that will turn the robot to the specified angle. */ +public class TurnToAngle extends PIDCommand { + /** + * Turns to robot to the specified angle. + * + * @param targetAngleDegrees The angle to turn to + * @param drive The drive subsystem to use + */ + public TurnToAngle(double targetAngleDegrees, DriveSystem drive) { + super( + new edu.wpi.first.math.controller.PIDController(Constants.kTurnP, Constants.kTurnI, Constants.kTurnD), + + drive::getHeading, + + targetAngleDegrees + drive.getStartingAngle(), + + output -> drive.drive(0, -output), + + drive); + + // Set the controller to be continuous (because it is an angle controller) + getController().enableContinuousInput(-180, 180); + // Set the controller tolerance - the delta tolerance ensures the robot is stationary at the + // setpoint before it is considered as having reached the reference + getController() + .setTolerance(Constants.kTurnToleranceDeg, Constants.kTurnRateToleranceDegPerS); + } + + + @Override + public void initialize(){ + System.out.println("Turning"); + } + @Override + public boolean isFinished() { + // End when the controller is at the reference. + return getController().atSetpoint(); + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/DriveSystem.java b/src/main/java/frc/robot/subsystems/DriveSystem.java index 912d97a..23c1f82 100644 --- a/src/main/java/frc/robot/subsystems/DriveSystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSystem.java @@ -4,10 +4,22 @@ package frc.robot.subsystems; +import com.kauailabs.navx.frc.AHRS; + +import org.photonvision.PhotonCamera; +import org.photonvision.PhotonUtils; +import org.photonvision.targeting.PhotonPipelineResult; + +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.SerialPort; import edu.wpi.first.wpilibj.drive.DifferentialDrive; +import edu.wpi.first.wpilibj.interfaces.Gyro; import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.VictorSP; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants; public class DriveSystem extends SubsystemBase { /** Creates a new ExampleSubsystem. */ @@ -21,15 +33,51 @@ public class DriveSystem extends SubsystemBase { MotorControllerGroup rightMotors = new MotorControllerGroup(rightMotorFront, rightMotorBack); MotorControllerGroup leftMotors = new MotorControllerGroup(leftMotorFront, leftMotorBack); + Gyro gyro = new AHRS(SerialPort.Port.kMXP); /* Alternatives: SPI.Port.kMXP, I2C.Port.kMXP or SerialPort.Port.kUSB */ + + Double gyroBaseAngle = 0.0; + + //Vision + private PhotonCamera cam = new PhotonCamera(Constants.Vision.kCamName); + public PhotonCamera getCamera(){ + return cam; + } + private final DifferentialDrive m_robotDrive = new DifferentialDrive(leftMotors, rightMotors); public DriveSystem() { leftMotors.setInverted(true); + gyroBaseAngle = gyro.getAngle(); + } + + public double getHeading() { + return gyro.getAngle(); } @Override public void periodic() { // This method will be called once per scheduler run + SmartDashboard.putNumber("Gyro Angle", gyro.getAngle()); + PhotonPipelineResult result = getCamera().getLatestResult(); + + if (result.hasTargets()) { + + // First calculate range + + double range = + + PhotonUtils.calculateDistanceToTargetMeters( + + Units.inchesToMeters(6.70), + + Constants.Vision.targetHeight, + + Units.degreesToRadians(45), + + Units.degreesToRadians(result.getBestTarget().getPitch())); + + SmartDashboard.putNumber("driverRange", range); + } } @Override @@ -38,6 +86,15 @@ public void simulationPeriodic() { } public void drive(double d, double e) { - m_robotDrive.arcadeDrive(-d, e, false); + m_robotDrive.arcadeDrive(-d*0.5, e*0.5, false); + } + + public void resetGyro(){ + gyro.reset(); + gyro.calibrate(); + } + + public Double getStartingAngle(){ + return gyroBaseAngle; } } diff --git a/vendordeps/navx_frc.json b/vendordeps/navx_frc.json new file mode 100644 index 0000000..0fb49a7 --- /dev/null +++ b/vendordeps/navx_frc.json @@ -0,0 +1,35 @@ +{ + "fileName": "navx_frc.json", + "name": "KauaiLabs_navX_FRC", + "version": "4.0.442", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "mavenUrls": [ + "https://repo1.maven.org/maven2/" + ], + "jsonUrl": "https://www.kauailabs.com/dist/frc/2022/navx_frc.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-java", + "version": "4.0.442" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-cpp", + "version": "4.0.442", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": false, + "libName": "navx_frc", + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json new file mode 100644 index 0000000..9a31b1e --- /dev/null +++ b/vendordeps/photonlib.json @@ -0,0 +1,41 @@ +{ + "fileName": "photonlib.json", + "name": "photonlib", + "version": "v2022.1.5", + "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004 ", + "mavenUrls": [ + "https://maven.photonvision.org/repository/internal", + "https://maven.photonvision.org/repository/snapshots" + ], + "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/PhotonLib-json/1.0/PhotonLib-json-1.0.json", + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "PhotonLib-cpp", + "version": "v2022.1.5", + "libName": "Photon", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxx86-64" + ] + } + ], + "javaDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "PhotonLib-java", + "version": "v2022.1.5" + }, + { + "groupId": "org.photonvision", + "artifactId": "PhotonTargeting-java", + "version": "v2022.1.5" + } + ] +} \ No newline at end of file