From b91e98232c6225b89dd847477549127ac2a70bd2 Mon Sep 17 00:00:00 2001 From: Soham Patil Date: Thu, 14 Nov 2024 20:27:38 -0500 Subject: [PATCH] removed all instances of cancoders --- .../swervev3/io/SparkMaxModuleIO.java | 8 ++-- .../swervev2/EncodedSwerveMotorBuilder.java | 5 ++- .../components/EncodedSwerveSparkMax.java | 4 +- .../components/GenericEncodedSwerve.java | 14 +++---- .../utils/diag/DiagSparkMaxAbsEncoder.java | 8 ++-- vendordeps/photonlib.json | 42 ------------------- 6 files changed, 20 insertions(+), 61 deletions(-) delete mode 100644 vendordeps/photonlib.json diff --git a/src/main/java/frc/robot/subsystems/swervev3/io/SparkMaxModuleIO.java b/src/main/java/frc/robot/subsystems/swervev3/io/SparkMaxModuleIO.java index 008245c9..1247c6fd 100644 --- a/src/main/java/frc/robot/subsystems/swervev3/io/SparkMaxModuleIO.java +++ b/src/main/java/frc/robot/subsystems/swervev3/io/SparkMaxModuleIO.java @@ -1,6 +1,6 @@ package frc.robot.subsystems.swervev3.io; -import com.ctre.phoenix.sensors.WPI_CANCoder; +import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.CANSparkMax; import frc.robot.constants.Constants; import frc.robot.swervev2.KinematicsConversionConfig; @@ -11,13 +11,13 @@ public class SparkMaxModuleIO implements ModuleIO { private final CANSparkMax driveMotor; private final CANSparkMax steerMotor; - private final WPI_CANCoder absEncoder; + private final CANcoder absEncoder; private final AtomicLong steerOffset = new AtomicLong(0); public SparkMaxModuleIO(SwerveIdConfig motorConfig, KinematicsConversionConfig conversionConfig, boolean driveInverted, boolean steerInverted) { driveMotor = new CANSparkMax(motorConfig.getDriveMotorId(), CANSparkMax.MotorType.kBrushless); steerMotor = new CANSparkMax(motorConfig.getTurnMotorId(), CANSparkMax.MotorType.kBrushless); - absEncoder = new WPI_CANCoder(motorConfig.getCanCoderId()); + absEncoder = new CANcoder(motorConfig.getCanCoderId()); setMotorConfig(driveInverted, steerInverted); setConversionFactors(conversionConfig); resetEncoder(); @@ -58,7 +58,7 @@ public void setSteerVoltage(double volts) { @Override public void setSteerOffset(double zeroAbs) { steerMotor.getEncoder().setPosition(0); - steerOffset.set(Double.doubleToLongBits(normalizeAngle(Math.toRadians(zeroAbs - absEncoder.getAbsolutePosition())))); + steerOffset.set(Double.doubleToLongBits(normalizeAngle(Math.toRadians(zeroAbs - absEncoder.getAbsolutePosition().getValueAsDouble())))); } private double normalizeAngle(double angleInRad) { diff --git a/src/main/java/frc/robot/swervev2/EncodedSwerveMotorBuilder.java b/src/main/java/frc/robot/swervev2/EncodedSwerveMotorBuilder.java index dcf3c3b1..414dc05f 100644 --- a/src/main/java/frc/robot/swervev2/EncodedSwerveMotorBuilder.java +++ b/src/main/java/frc/robot/swervev2/EncodedSwerveMotorBuilder.java @@ -1,6 +1,7 @@ package frc.robot.swervev2; -import com.ctre.phoenix.sensors.WPI_CANCoder; + +import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.CANSparkMax; import frc.robot.constants.Constants; import frc.robot.swervev2.components.EncodedSwerveSparkMax; @@ -22,7 +23,7 @@ public EncodedSwerveMotorBuilder(SwerveIdConfig motorConfig, KinematicsConversio public EncodedSwerveSparkMax build(){ CANSparkMax driveMotor = new CANSparkMax(motorConfig.getDriveMotorId(), CANSparkMax.MotorType.kBrushless); CANSparkMax turnMotor = new CANSparkMax(motorConfig.getTurnMotorId(), CANSparkMax.MotorType.kBrushless); - WPI_CANCoder canCoder = new WPI_CANCoder(motorConfig.getCanCoderId()); + CANcoder canCoder = new CANcoder(motorConfig.getCanCoderId()); double driveVelConvFactor = (2 * conversionConfig.getWheelRadius() * Math.PI) / (conversionConfig.getDriveGearRatio() * 60); double drivePosConvFactor = (2 * conversionConfig.getWheelRadius() * Math.PI) / (conversionConfig.getDriveGearRatio()); double steerPosConvFactor = 2 * Math.PI / Constants.SWERVE_MODULE_PROFILE.getSteerRatio(); diff --git a/src/main/java/frc/robot/swervev2/components/EncodedSwerveSparkMax.java b/src/main/java/frc/robot/swervev2/components/EncodedSwerveSparkMax.java index bc8eaeaa..557f3698 100644 --- a/src/main/java/frc/robot/swervev2/components/EncodedSwerveSparkMax.java +++ b/src/main/java/frc/robot/swervev2/components/EncodedSwerveSparkMax.java @@ -1,11 +1,11 @@ package frc.robot.swervev2.components; -import com.ctre.phoenix.sensors.WPI_CANCoder; +import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.CANSparkMax; import frc.robot.constants.Constants; public class EncodedSwerveSparkMax extends GenericEncodedSwerve { - public EncodedSwerveSparkMax(CANSparkMax driveMotor, CANSparkMax steerMotor, WPI_CANCoder absEncoder, double driveVelFactor, double drivePosFactor, double steerPosFactor) { + public EncodedSwerveSparkMax(CANSparkMax driveMotor, CANSparkMax steerMotor, CANcoder absEncoder, double driveVelFactor, double drivePosFactor, double steerPosFactor) { super(driveMotor, steerMotor, absEncoder, driveMotor.getEncoder(), steerMotor.getEncoder(), driveVelFactor, drivePosFactor, steerPosFactor); configureEncoders(driveVelFactor,drivePosFactor, steerPosFactor); } diff --git a/src/main/java/frc/robot/swervev2/components/GenericEncodedSwerve.java b/src/main/java/frc/robot/swervev2/components/GenericEncodedSwerve.java index e39cfac0..81905fc3 100644 --- a/src/main/java/frc/robot/swervev2/components/GenericEncodedSwerve.java +++ b/src/main/java/frc/robot/swervev2/components/GenericEncodedSwerve.java @@ -1,7 +1,7 @@ package frc.robot.swervev2.components; -import com.ctre.phoenix.sensors.CANCoderStatusFrame; -import com.ctre.phoenix.sensors.WPI_CANCoder; + +import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.RelativeEncoder; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; @@ -17,9 +17,9 @@ public class GenericEncodedSwerve implements SwerveMotor, SwerveMotorEncoder { private final RelativeEncoder driveEncoder; private final RelativeEncoder steerEncoder; private double steerOffset = 0; - private final WPI_CANCoder absEncoder; + private final CANcoder absEncoder; - public GenericEncodedSwerve(MotorController driveMotor, MotorController steerMotor, WPI_CANCoder absEncoder, RelativeEncoder driveEncoder, RelativeEncoder steerEncoder, + public GenericEncodedSwerve(MotorController driveMotor, MotorController steerMotor, CANcoder absEncoder, RelativeEncoder driveEncoder, RelativeEncoder steerEncoder, double driveVelFactor, double drivePosFactor, double steerPosFactor) { this.driveMotor = driveMotor; this.steerMotor = steerMotor; @@ -41,7 +41,7 @@ public void configureEncoders(double driveVelFactor, double drivePosFactor, doub driveEncoder.setPositionConversionFactor(drivePosFactor); steerEncoder.setPositionConversionFactor(steerPosFactor); steerEncoder.setVelocityConversionFactor(steerPosFactor/60); - absEncoder.setStatusFramePeriod(CANCoderStatusFrame.SensorData,50); + absEncoder.getPosition().setUpdateFrequency(50); //We think its 50 } @Override @@ -89,7 +89,7 @@ public double getSteerOffset() { @Override public void setSteerOffset(double zeroAbs) { steerEncoder.setPosition(0); - steerOffset = Math.toRadians(zeroAbs - absEncoder.getAbsolutePosition()); + steerOffset = Math.toRadians(zeroAbs - absEncoder.getAbsolutePosition().getValueAsDouble()); steerOffset = normalizeAngle(steerOffset); } public SwerveModulePosition getPosition(){ @@ -108,7 +108,7 @@ private double normalizeAngle(double angleInRad){ return angleInRad; } - public WPI_CANCoder getAbsEnc() { + public CANcoder getAbsEnc() { return absEncoder; } diff --git a/src/main/java/frc/robot/utils/diag/DiagSparkMaxAbsEncoder.java b/src/main/java/frc/robot/utils/diag/DiagSparkMaxAbsEncoder.java index 347ed7cf..5d74f600 100644 --- a/src/main/java/frc/robot/utils/diag/DiagSparkMaxAbsEncoder.java +++ b/src/main/java/frc/robot/utils/diag/DiagSparkMaxAbsEncoder.java @@ -1,6 +1,6 @@ package frc.robot.utils.diag; -import com.ctre.phoenix.sensors.WPI_CANCoder; +import com.ctre.phoenix6.hardware.CANcoder; /** * A diagnostics class for digital encoder. The diagnostics will turn green once the encoder has traveled at least a given @@ -8,7 +8,7 @@ */ public class DiagSparkMaxAbsEncoder extends DiagDistanceTraveled { - private WPI_CANCoder canCoder; + private CANcoder canCoder; /** * Constructor @@ -17,7 +17,7 @@ public class DiagSparkMaxAbsEncoder extends DiagDistanceTraveled { * @param requiredTravel - the required difference between the initial position to qualify for success * @param canSparkMax - the encoder instance to test */ - public DiagSparkMaxAbsEncoder(String title, String name, double requiredTravel, WPI_CANCoder canCoder) { + public DiagSparkMaxAbsEncoder(String title, String name, double requiredTravel, CANcoder canCoder) { super(title, name, requiredTravel); this.canCoder = canCoder; reset(); @@ -25,6 +25,6 @@ public DiagSparkMaxAbsEncoder(String title, String name, double requiredTravel, @Override protected double getCurrentValue() { - return canCoder.getAbsolutePosition(); + return canCoder.getAbsolutePosition().getValueAsDouble(); } } diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json deleted file mode 100644 index c940b75b..00000000 --- a/vendordeps/photonlib.json +++ /dev/null @@ -1,42 +0,0 @@ -{ - "fileName": "photonlib.json", - "name": "photonlib", - "version": "v2024.1.1-beta-3.2", - "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", - "frcYear": "2024", - "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": "v2024.1.1-beta-3.2", - "libName": "Photon", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxathena", - "linuxx86-64", - "osxuniversal" - ] - } - ], - "javaDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "PhotonLib-java", - "version": "v2024.1.1-beta-3.2" - }, - { - "groupId": "org.photonvision", - "artifactId": "PhotonTargeting-java", - "version": "v2024.1.1-beta-3.2" - } - ] -} \ No newline at end of file