Skip to content

Commit 309b0a1

Browse files
committed
Import project to WPILib 2024
1 parent ae85963 commit 309b0a1

11 files changed

Lines changed: 88 additions & 53 deletions

File tree

.gitignore

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -158,5 +158,21 @@ gradle-app.setting
158158
.settings/
159159
bin/
160160

161+
# IntelliJ
162+
*.iml
163+
*.ipr
164+
*.iws
165+
.idea/
166+
out/
167+
168+
# Fleet
169+
.fleet
170+
161171
# Simulation GUI and other tools window save file
162172
*-window.json
173+
174+
# Simulation data log directory
175+
logs/
176+
177+
# Folder that has CTRE Phoenix Sim device config storage
178+
ctre_sim/

.wpilib/wpilib_preferences.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
{
22
"enableCppIntellisense": false,
33
"currentLanguage": "java",
4-
"projectYear": "2023",
4+
"projectYear": "2024",
55
"teamNumber": 2714
66
}

WPILib-License.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
Copyright (c) 2009-2021 FIRST and other WPILib contributors
1+
Copyright (c) 2009-2023 FIRST and other WPILib contributors
22
All rights reserved.
33

44
Redistribution and use in source and binary forms, with or without

build.gradle

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,12 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2023.2.1"
3+
id "edu.wpi.first.GradleRIO" version "2024.1.1"
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
def ROBOT_MAIN_CLASS = "frc.robot.Main"
1012

@@ -65,9 +67,8 @@ dependencies {
6567
nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop)
6668
simulationRelease wpi.sim.enableRelease()
6769

68-
testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2'
69-
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2'
70-
testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2'
70+
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
71+
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
7172
}
7273

7374
test {
@@ -84,6 +85,7 @@ wpi.sim.addDriverstation()
8485
// knows where to look for our Robot Class.
8586
jar {
8687
from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } }
88+
from sourceSets.main.allSource
8789
manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS)
8890
duplicatesStrategy = DuplicatesStrategy.INCLUDE
8991
}

gradle/wrapper/gradle-wrapper.jar

-16.9 KB
Binary file not shown.
Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
distributionBase=GRADLE_USER_HOME
22
distributionPath=permwrapper/dists
3-
distributionUrl=https\://services.gradle.org/distributions/gradle-7.5.1-bin.zip
3+
distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip
4+
networkTimeout=10000
5+
validateDistributionUrl=true
46
zipStoreBase=GRADLE_USER_HOME
57
zipStorePath=permwrapper/dists

gradlew

Lines changed: 22 additions & 13 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

gradlew.bat

Lines changed: 1 addition & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

settings.gradle

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ pluginManagement {
44
repositories {
55
mavenLocal()
66
gradlePluginPortal()
7-
String frcYear = '2023'
7+
String frcYear = '2024'
88
File frcHome
99
if (OperatingSystem.current().isWindows()) {
1010
String publicFolder = System.getenv('PUBLIC')
@@ -25,3 +25,6 @@ pluginManagement {
2525
}
2626
}
2727
}
28+
29+
Properties props = System.getProperties();
30+
props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true");

src/main/java/frc/robot/subsystems/DriveSubsystem.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import edu.wpi.first.math.kinematics.SwerveModuleState;
1515
import edu.wpi.first.util.WPIUtilJNI;
1616
import edu.wpi.first.wpilibj.ADIS16470_IMU;
17+
import edu.wpi.first.wpilibj.ADIS16470_IMU.IMUAxis;
1718
import frc.robot.Constants.DriveConstants;
1819
import frc.utils.SwerveUtils;
1920
import edu.wpi.first.wpilibj2.command.SubsystemBase;
@@ -55,7 +56,7 @@ public class DriveSubsystem extends SubsystemBase {
5556
// Odometry class for tracking robot pose
5657
SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(
5758
DriveConstants.kDriveKinematics,
58-
Rotation2d.fromDegrees(m_gyro.getAngle()),
59+
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
5960
new SwerveModulePosition[] {
6061
m_frontLeft.getPosition(),
6162
m_frontRight.getPosition(),
@@ -71,7 +72,7 @@ public DriveSubsystem() {
7172
public void periodic() {
7273
// Update the odometry in the periodic block
7374
m_odometry.update(
74-
Rotation2d.fromDegrees(m_gyro.getAngle()),
75+
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
7576
new SwerveModulePosition[] {
7677
m_frontLeft.getPosition(),
7778
m_frontRight.getPosition(),
@@ -96,7 +97,7 @@ public Pose2d getPose() {
9697
*/
9798
public void resetOdometry(Pose2d pose) {
9899
m_odometry.resetPosition(
99-
Rotation2d.fromDegrees(m_gyro.getAngle()),
100+
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
100101
new SwerveModulePosition[] {
101102
m_frontLeft.getPosition(),
102103
m_frontRight.getPosition(),
@@ -176,7 +177,7 @@ else if (angleDif > 0.85*Math.PI) {
176177

177178
var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
178179
fieldRelative
179-
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered, Rotation2d.fromDegrees(m_gyro.getAngle()))
180+
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered, Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)))
180181
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
181182
SwerveDriveKinematics.desaturateWheelSpeeds(
182183
swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond);
@@ -229,7 +230,7 @@ public void zeroHeading() {
229230
* @return the robot's heading in degrees, from -180 to 180
230231
*/
231232
public double getHeading() {
232-
return Rotation2d.fromDegrees(m_gyro.getAngle()).getDegrees();
233+
return Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)).getDegrees();
233234
}
234235

235236
/**
@@ -238,6 +239,6 @@ public double getHeading() {
238239
* @return The turn rate of the robot, in degrees per second
239240
*/
240241
public double getTurnRate() {
241-
return m_gyro.getRate() * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
242+
return m_gyro.getRate(IMUAxis.kZ) * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
242243
}
243244
}

0 commit comments

Comments
 (0)