Skip to content

Commit 8d0e062

Browse files
committed
Update for 2024- waiting on Phoenix
1 parent 7693298 commit 8d0e062

26 files changed

+610
-493
lines changed

build.gradle

+7-4
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,10 @@ plugins {
33
id 'maven-publish'
44
}
55

6-
sourceCompatibility = JavaVersion.VERSION_11
7-
targetCompatibility = JavaVersion.VERSION_11
6+
java {
7+
sourceCompatibility = JavaVersion.VERSION_17
8+
targetCompatibility = JavaVersion.VERSION_17
9+
}
810

911
allprojects {
1012
group 'com.swervedrivespecialties'
@@ -27,10 +29,11 @@ dependencies {
2729
implementation "edu.wpi.first.wpilibj:wpilibj-java:${wpilib_version}"
2830
implementation "edu.wpi.first.wpiutil:wpiutil-java:${wpilib_version}"
2931
implementation "edu.wpi.first.wpimath:wpimath-java:${wpilib_version}"
32+
implementation "edu.wpi.first.wpiunits:wpiunits-java:${wpilib_version}"
3033

3134
// CTRE is implementation because it is not a hard requirement
32-
implementation "com.ctre.phoenix:api-java:${ctre_phoenix_version}"
33-
implementation "com.ctre.phoenix:wpiapi-java:${ctre_phoenix_version}"
35+
// implementation "com.ctre.phoenix6:api-java:${ctre_phoenix_version}"
36+
implementation "com.ctre.phoenix6:wpiapi-java:${ctre_phoenix_version}"
3437

3538
// REV is implementation because it is not a hard requirement
3639
implementation "com.revrobotics.frc:REVLib-java:${revlib_version}"

examples/mk3-minibot/build.gradle

+5-3
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,17 @@
11
plugins {
22
id 'application'
33
id 'com.github.johnrengelman.shadow'
4-
id 'edu.wpi.first.GradleRIO' version "2023.2.1"
4+
id 'edu.wpi.first.GradleRIO' version "2024.1.1"
55
}
66

77
application {
88
mainClass.set('com.swervedrivespecialties.examples.mk3minibot.Main')
99
}
1010

11-
targetCompatibility = JavaVersion.VERSION_11
12-
sourceCompatibility = JavaVersion.VERSION_11
11+
java {
12+
sourceCompatibility = JavaVersion.VERSION_17
13+
targetCompatibility = JavaVersion.VERSION_17
14+
}
1315

1416
deploy {
1517
targets {

examples/mk3-minibot/src/main/java/com/swervedrivespecialties/examples/mk3minibot/commands/DriveCommand.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,11 @@
22

33
import com.swervedrivespecialties.examples.mk3minibot.subsystems.DrivetrainSubsystem;
44
import edu.wpi.first.math.kinematics.ChassisSpeeds;
5-
import edu.wpi.first.wpilibj2.command.CommandBase;
5+
import edu.wpi.first.wpilibj2.command.Command;
66

77
import java.util.function.DoubleSupplier;
88

9-
public class DriveCommand extends CommandBase {
9+
public class DriveCommand extends Command {
1010
private final DrivetrainSubsystem drivetrain;
1111
private final DoubleSupplier translationXSupplier;
1212
private final DoubleSupplier translationYSupplier;

examples/mk3-minibot/src/main/java/com/swervedrivespecialties/examples/mk3minibot/subsystems/DrivetrainSubsystem.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
package com.swervedrivespecialties.examples.mk3minibot.subsystems;
22

3-
import com.ctre.phoenix.sensors.PigeonIMU;
3+
import com.ctre.phoenix6.hardware.Pigeon2;
44
import com.swervedrivespecialties.examples.mk3minibot.Constants;
55
import com.swervedrivespecialties.swervelib.MkSwerveModuleBuilder;
66
import com.swervedrivespecialties.swervelib.MotorType;
@@ -30,7 +30,7 @@ public class DrivetrainSubsystem extends SubsystemBase {
3030
private final SwerveModule backLeftModule;
3131
private final SwerveModule backRightModule;
3232

33-
private final PigeonIMU gyroscope = new PigeonIMU(Constants.DRIVETRAIN_PIGEON_ID);
33+
private final Pigeon2 gyroscope = new Pigeon2(Constants.DRIVETRAIN_PIGEON_ID);
3434

3535
private final SwerveDriveKinematics kinematics = new SwerveDriveKinematics(
3636
new Translation2d(Constants.DRIVETRAIN_TRACKWIDTH_METERS / 2.0, Constants.DRIVETRAIN_WHEELBASE_METERS / 2.0),
@@ -91,7 +91,7 @@ public DrivetrainSubsystem() {
9191

9292
odometry = new SwerveDriveOdometry(
9393
kinematics,
94-
Rotation2d.fromDegrees(gyroscope.getFusedHeading()),
94+
Rotation2d.fromDegrees(gyroscope.getAngle()),
9595
new SwerveModulePosition[]{ frontLeftModule.getPosition(), frontRightModule.getPosition(), backLeftModule.getPosition(), backRightModule.getPosition() }
9696
);
9797

@@ -102,7 +102,7 @@ public DrivetrainSubsystem() {
102102

103103
public void zeroGyroscope() {
104104
odometry.resetPosition(
105-
Rotation2d.fromDegrees(gyroscope.getFusedHeading()),
105+
Rotation2d.fromDegrees(gyroscope.getAngle()),
106106
new SwerveModulePosition[]{ frontLeftModule.getPosition(), frontRightModule.getPosition(), backLeftModule.getPosition(), backRightModule.getPosition() },
107107
new Pose2d(odometry.getPoseMeters().getTranslation(), Rotation2d.fromDegrees(0.0))
108108
);
@@ -119,7 +119,7 @@ public void drive(ChassisSpeeds chassisSpeeds) {
119119
@Override
120120
public void periodic() {
121121
odometry.update(
122-
Rotation2d.fromDegrees(gyroscope.getFusedHeading()),
122+
Rotation2d.fromDegrees(gyroscope.getAngle()),
123123
new SwerveModulePosition[]{ frontLeftModule.getPosition(), frontRightModule.getPosition(), backLeftModule.getPosition(), backRightModule.getPosition() }
124124
);
125125

0 commit comments

Comments
 (0)