Skip to content

Commit 7f7c62c

Browse files
authored
Merge pull request #26 from REVrobotics/2025-update
Update for 2025
2 parents e87ac7a + 97b4a89 commit 7f7c62c

19 files changed

+148
-313
lines changed

.gitignore

+6
Original file line numberDiff line numberDiff line change
@@ -169,10 +169,16 @@ out/
169169
.fleet
170170

171171
# Simulation GUI and other tools window save file
172+
networktables.json
173+
simgui.json
172174
*-window.json
173175

174176
# Simulation data log directory
175177
logs/
176178

177179
# Folder that has CTRE Phoenix Sim device config storage
178180
ctre_sim/
181+
182+
# clangd
183+
/.cache
184+
compile_commands.json

.wpilib/wpilib_preferences.json

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
{
22
"enableCppIntellisense": false,
33
"currentLanguage": "java",
4-
"projectYear": "2024",
4+
"projectYear": "2025beta",
55
"teamNumber": 2714
66
}

CHANGELOG.md

+6
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,11 @@
11
# MAXSwerve Java Template Changelog
22

3+
## [2025.0] - 2024-11-07
4+
5+
- Updates project for 2025 FRC season
6+
- Uses new SPARK configuration mechanism introduced in REVLib 2025
7+
- Removes slew rate limiter since it is no longer needed with MAXSwerve 2.0 wheels
8+
39
## [2024.0] - 2024-01-08
410

511
- Updates project for 2024 FRC season

README.md

+4-4
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# MAXSwerve Java Template v2024.0
1+
# MAXSwerve Java Template v2025.0
22

33
See [the online changelog](https://github.com/REVrobotics/MAXSwerve-Java-Template/blob/main/CHANGELOG.md) for information about updates to the template that may have been released since you created your project.
44

@@ -12,11 +12,11 @@ To get started, make sure you have calibrated the zero offsets for the absolute
1212

1313
## Prerequisites
1414

15-
* SPARK MAX Firmware v1.6.2 - Adds features that are required for swerve
16-
* REVLib v2023.1.2 - Includes APIs for the new firmware features
15+
* SPARK MAX Firmware v25.0.0
16+
* REVLib v2025.0.0
1717

1818
## Configuration
1919

2020
It is possible that this project will not work for your robot right out of the box. Various things like the CAN IDs, PIDF gains, chassis configuration, etc. must be determined for your own robot!
2121

22-
These values can be adjusted in the `Constants.java` file.
22+
These values can be adjusted in the `Configs.java` and `Constants.java` files.

WPILib-License.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
Copyright (c) 2009-2023 FIRST and other WPILib contributors
1+
Copyright (c) 2009-2024 FIRST and other WPILib contributors
22
All rights reserved.
33

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

build.gradle

+2-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2024.1.1"
3+
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
44
}
55

66
java {
@@ -50,6 +50,7 @@ def includeDesktopSupport = false
5050
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
5151
// Also defines JUnit 5.
5252
dependencies {
53+
annotationProcessor wpi.java.deps.wpilibAnnotations()
5354
implementation wpi.java.deps.wpilib()
5455
implementation wpi.java.vendor.java()
5556

gradle/wrapper/gradle-wrapper.jar

121 Bytes
Binary file not shown.

gradle/wrapper/gradle-wrapper.properties

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
distributionBase=GRADLE_USER_HOME
22
distributionPath=permwrapper/dists
3-
distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip
3+
distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip
44
networkTimeout=10000
55
validateDistributionUrl=true
66
zipStoreBase=GRADLE_USER_HOME

gradlew

+5-2
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
# See the License for the specific language governing permissions and
1616
# limitations under the License.
1717
#
18+
# SPDX-License-Identifier: Apache-2.0
19+
#
1820

1921
##############################################################################
2022
#
@@ -55,7 +57,7 @@
5557
# Darwin, MinGW, and NonStop.
5658
#
5759
# (3) This script is generated from the Groovy template
58-
# https://github.com/gradle/gradle/blob/HEAD/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt
60+
# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt
5961
# within the Gradle project.
6062
#
6163
# You can find Gradle at https://github.com/gradle/gradle/.
@@ -84,7 +86,8 @@ done
8486
# shellcheck disable=SC2034
8587
APP_BASE_NAME=${0##*/}
8688
# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036)
87-
APP_HOME=$( cd "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit
89+
APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s
90+
' "$PWD" ) || exit
8891

8992
# Use the maximum available, or set MAX_FD != -1 to use that value.
9093
MAX_FD=maximum

gradlew.bat

+12-10
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
@rem See the License for the specific language governing permissions and
1414
@rem limitations under the License.
1515
@rem
16+
@rem SPDX-License-Identifier: Apache-2.0
17+
@rem
1618

1719
@if "%DEBUG%"=="" @echo off
1820
@rem ##########################################################################
@@ -43,11 +45,11 @@ set JAVA_EXE=java.exe
4345
%JAVA_EXE% -version >NUL 2>&1
4446
if %ERRORLEVEL% equ 0 goto execute
4547

46-
echo.
47-
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
48-
echo.
49-
echo Please set the JAVA_HOME variable in your environment to match the
50-
echo location of your Java installation.
48+
echo. 1>&2
49+
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2
50+
echo. 1>&2
51+
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
52+
echo location of your Java installation. 1>&2
5153

5254
goto fail
5355

@@ -57,11 +59,11 @@ set JAVA_EXE=%JAVA_HOME%/bin/java.exe
5759

5860
if exist "%JAVA_EXE%" goto execute
5961

60-
echo.
61-
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME%
62-
echo.
63-
echo Please set the JAVA_HOME variable in your environment to match the
64-
echo location of your Java installation.
62+
echo. 1>&2
63+
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2
64+
echo. 1>&2
65+
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
66+
echo location of your Java installation. 1>&2
6567

6668
goto fail
6769

settings.gradle

+1-1
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ pluginManagement {
44
repositories {
55
mavenLocal()
66
gradlePluginPortal()
7-
String frcYear = '2024'
7+
String frcYear = '2025'
88
File frcHome
99
if (OperatingSystem.current().isWindows()) {
1010
String publicFolder = System.getenv('PUBLIC')

src/main/java/frc/robot/Configs.java

+56
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
package frc.robot;
2+
3+
import com.revrobotics.spark.config.SparkMaxConfig;
4+
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
5+
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
6+
7+
import frc.robot.Constants.ModuleConstants;
8+
9+
public final class Configs {
10+
public static final class MAXSwerveModule {
11+
public static final SparkMaxConfig drivingConfig = new SparkMaxConfig();
12+
public static final SparkMaxConfig turningConfig = new SparkMaxConfig();
13+
14+
static {
15+
// Use module constants to calculate conversion factors and feed forward gain.
16+
double drivingFactor = ModuleConstants.kWheelDiameterMeters * Math.PI
17+
/ ModuleConstants.kDrivingMotorReduction;
18+
double turningFactor = 2 * Math.PI;
19+
double drivingVelocityFeedForward = 1 / ModuleConstants.kDriveWheelFreeSpeedRps;
20+
21+
drivingConfig
22+
.idleMode(IdleMode.kBrake)
23+
.smartCurrentLimit(50);
24+
drivingConfig.encoder
25+
.positionConversionFactor(drivingFactor) // meters
26+
.velocityConversionFactor(drivingFactor / 60.0); // meters per second
27+
drivingConfig.closedLoop
28+
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
29+
// These are example gains you may need to them for your own robot!
30+
.pid(0.04, 0, 0)
31+
.velocityFF(drivingVelocityFeedForward)
32+
.outputRange(-1, 1);
33+
34+
turningConfig
35+
.idleMode(IdleMode.kBrake)
36+
.smartCurrentLimit(20);
37+
turningConfig.absoluteEncoder
38+
// Invert the turning encoder, since the output shaft rotates in the opposite
39+
// direction of the steering motor in the MAXSwerve Module.
40+
.inverted(true)
41+
.positionConversionFactor(turningFactor) // radians
42+
.velocityConversionFactor(turningFactor / 60.0); // radians per second
43+
turningConfig.closedLoop
44+
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
45+
// These are example gains you may need to them for your own robot!
46+
.pid(1, 0, 0)
47+
.outputRange(-1, 1)
48+
// Enable PID wrap around for the turning motor. This will allow the PID
49+
// controller to go through 0 to get to the setpoint i.e. going from 350 degrees
50+
// to 10 degrees will go through 0 rather than the other direction which is a
51+
// longer route.
52+
.positionWrappingEnabled(true)
53+
.positionWrappingInputRange(0, turningFactor);
54+
}
55+
}
56+
}

src/main/java/frc/robot/Constants.java

+5-41
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,6 @@
44

55
package frc.robot;
66

7-
import com.revrobotics.CANSparkBase.IdleMode;
8-
97
import edu.wpi.first.math.geometry.Translation2d;
108
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
119
import edu.wpi.first.math.trajectory.TrapezoidProfile;
@@ -66,54 +64,20 @@ public static final class DriveConstants {
6664
}
6765

6866
public static final class ModuleConstants {
69-
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
70-
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
71-
// robot that drives faster).
67+
// The MAXSwerve module can be configured with one of three pinion gears: 12T,
68+
// 13T, or 14T. This changes the drive speed of the module (a pinion gear with
69+
// more teeth will result in a robot that drives faster).
7270
public static final int kDrivingMotorPinionTeeth = 14;
7371

74-
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
75-
// the steering motor in the MAXSwerve Module.
76-
public static final boolean kTurningEncoderInverted = true;
77-
7872
// Calculations required for driving motor conversion factors and feed forward
7973
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
8074
public static final double kWheelDiameterMeters = 0.0762;
8175
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
82-
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
76+
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15
77+
// teeth on the bevel pinion
8378
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
8479
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
8580
/ kDrivingMotorReduction;
86-
87-
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
88-
/ kDrivingMotorReduction; // meters
89-
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
90-
/ kDrivingMotorReduction) / 60.0; // meters per second
91-
92-
public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
93-
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
94-
95-
public static final double kTurningEncoderPositionPIDMinInput = 0; // radians
96-
public static final double kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor; // radians
97-
98-
public static final double kDrivingP = 0.04;
99-
public static final double kDrivingI = 0;
100-
public static final double kDrivingD = 0;
101-
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
102-
public static final double kDrivingMinOutput = -1;
103-
public static final double kDrivingMaxOutput = 1;
104-
105-
public static final double kTurningP = 1;
106-
public static final double kTurningI = 0;
107-
public static final double kTurningD = 0;
108-
public static final double kTurningFF = 0;
109-
public static final double kTurningMinOutput = -1;
110-
public static final double kTurningMaxOutput = 1;
111-
112-
public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
113-
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;
114-
115-
public static final int kDrivingMotorCurrentLimit = 50; // amps
116-
public static final int kTurningMotorCurrentLimit = 20; // amps
11781
}
11882

11983
public static final class OIConstants {

src/main/java/frc/robot/RobotContainer.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ public RobotContainer() {
5454
-MathUtil.applyDeadband(m_driverController.getLeftY(), OIConstants.kDriveDeadband),
5555
-MathUtil.applyDeadband(m_driverController.getLeftX(), OIConstants.kDriveDeadband),
5656
-MathUtil.applyDeadband(m_driverController.getRightX(), OIConstants.kDriveDeadband),
57-
true, true),
57+
true),
5858
m_robotDrive));
5959
}
6060

@@ -117,6 +117,6 @@ public Command getAutonomousCommand() {
117117
m_robotDrive.resetOdometry(exampleTrajectory.getInitialPose());
118118

119119
// Run path following command, then stop at the end.
120-
return swerveControllerCommand.andThen(() -> m_robotDrive.drive(0, 0, 0, false, false));
120+
return swerveControllerCommand.andThen(() -> m_robotDrive.drive(0, 0, 0, false));
121121
}
122122
}

0 commit comments

Comments
 (0)