Skip to content

Commit

Permalink
Merge pull request #26 from REVrobotics/2025-update
Browse files Browse the repository at this point in the history
Update for 2025
  • Loading branch information
jfabellera authored Nov 16, 2024
2 parents e87ac7a + 97b4a89 commit 7f7c62c
Show file tree
Hide file tree
Showing 19 changed files with 148 additions and 313 deletions.
6 changes: 6 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -169,10 +169,16 @@ out/
.fleet

# Simulation GUI and other tools window save file
networktables.json
simgui.json
*-window.json

# Simulation data log directory
logs/

# Folder that has CTRE Phoenix Sim device config storage
ctre_sim/

# clangd
/.cache
compile_commands.json
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"projectYear": "2025beta",
"teamNumber": 2714
}
6 changes: 6 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,11 @@
# MAXSwerve Java Template Changelog

## [2025.0] - 2024-11-07

- Updates project for 2025 FRC season
- Uses new SPARK configuration mechanism introduced in REVLib 2025
- Removes slew rate limiter since it is no longer needed with MAXSwerve 2.0 wheels

## [2024.0] - 2024-01-08

- Updates project for 2024 FRC season
Expand Down
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# MAXSwerve Java Template v2024.0
# MAXSwerve Java Template v2025.0

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.

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

## Prerequisites

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

## Configuration

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!

These values can be adjusted in the `Constants.java` file.
These values can be adjusted in the `Configs.java` and `Constants.java` files.
2 changes: 1 addition & 1 deletion WPILib-License.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
Copyright (c) 2009-2023 FIRST and other WPILib contributors
Copyright (c) 2009-2024 FIRST and other WPILib contributors
All rights reserved.

Redistribution and use in source and binary forms, with or without
Expand Down
3 changes: 2 additions & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
}

java {
Expand Down Expand Up @@ -50,6 +50,7 @@ def includeDesktopSupport = false
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 5.
dependencies {
annotationProcessor wpi.java.deps.wpilibAnnotations()
implementation wpi.java.deps.wpilib()
implementation wpi.java.vendor.java()

Expand Down
Binary file modified gradle/wrapper/gradle-wrapper.jar
Binary file not shown.
2 changes: 1 addition & 1 deletion gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME
Expand Down
7 changes: 5 additions & 2 deletions gradlew
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0
#

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

# Use the maximum available, or set MAX_FD != -1 to use that value.
MAX_FD=maximum
Expand Down
22 changes: 12 additions & 10 deletions gradlew.bat
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
@rem See the License for the specific language governing permissions and
@rem limitations under the License.
@rem
@rem SPDX-License-Identifier: Apache-2.0
@rem

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

echo.
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
echo.
echo Please set the JAVA_HOME variable in your environment to match the
echo location of your Java installation.
echo. 1>&2
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2

goto fail

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

if exist "%JAVA_EXE%" goto execute

echo.
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME%
echo.
echo Please set the JAVA_HOME variable in your environment to match the
echo location of your Java installation.
echo. 1>&2
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2

goto fail

Expand Down
2 changes: 1 addition & 1 deletion settings.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2024'
String frcYear = '2025'
File frcHome
if (OperatingSystem.current().isWindows()) {
String publicFolder = System.getenv('PUBLIC')
Expand Down
56 changes: 56 additions & 0 deletions src/main/java/frc/robot/Configs.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
package frc.robot;

import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import frc.robot.Constants.ModuleConstants;

public final class Configs {
public static final class MAXSwerveModule {
public static final SparkMaxConfig drivingConfig = new SparkMaxConfig();
public static final SparkMaxConfig turningConfig = new SparkMaxConfig();

static {
// Use module constants to calculate conversion factors and feed forward gain.
double drivingFactor = ModuleConstants.kWheelDiameterMeters * Math.PI
/ ModuleConstants.kDrivingMotorReduction;
double turningFactor = 2 * Math.PI;
double drivingVelocityFeedForward = 1 / ModuleConstants.kDriveWheelFreeSpeedRps;

drivingConfig
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(50);
drivingConfig.encoder
.positionConversionFactor(drivingFactor) // meters
.velocityConversionFactor(drivingFactor / 60.0); // meters per second
drivingConfig.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
// These are example gains you may need to them for your own robot!
.pid(0.04, 0, 0)
.velocityFF(drivingVelocityFeedForward)
.outputRange(-1, 1);

turningConfig
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(20);
turningConfig.absoluteEncoder
// Invert the turning encoder, since the output shaft rotates in the opposite
// direction of the steering motor in the MAXSwerve Module.
.inverted(true)
.positionConversionFactor(turningFactor) // radians
.velocityConversionFactor(turningFactor / 60.0); // radians per second
turningConfig.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
// These are example gains you may need to them for your own robot!
.pid(1, 0, 0)
.outputRange(-1, 1)
// Enable PID wrap around for the turning motor. This will allow the PID
// controller to go through 0 to get to the setpoint i.e. going from 350 degrees
// to 10 degrees will go through 0 rather than the other direction which is a
// longer route.
.positionWrappingEnabled(true)
.positionWrappingInputRange(0, turningFactor);
}
}
}
46 changes: 5 additions & 41 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@

package frc.robot;

import com.revrobotics.CANSparkBase.IdleMode;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
Expand Down Expand Up @@ -66,54 +64,20 @@ public static final class DriveConstants {
}

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

// Invert the turning encoder, since the output shaft rotates in the opposite direction of
// the steering motor in the MAXSwerve Module.
public static final boolean kTurningEncoderInverted = true;

// Calculations required for driving motor conversion factors and feed forward
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
public static final double kWheelDiameterMeters = 0.0762;
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15
// teeth on the bevel pinion
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction;

public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction; // meters
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction) / 60.0; // meters per second

public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second

public static final double kTurningEncoderPositionPIDMinInput = 0; // radians
public static final double kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor; // radians

public static final double kDrivingP = 0.04;
public static final double kDrivingI = 0;
public static final double kDrivingD = 0;
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
public static final double kDrivingMinOutput = -1;
public static final double kDrivingMaxOutput = 1;

public static final double kTurningP = 1;
public static final double kTurningI = 0;
public static final double kTurningD = 0;
public static final double kTurningFF = 0;
public static final double kTurningMinOutput = -1;
public static final double kTurningMaxOutput = 1;

public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;

public static final int kDrivingMotorCurrentLimit = 50; // amps
public static final int kTurningMotorCurrentLimit = 20; // amps
}

public static final class OIConstants {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public RobotContainer() {
-MathUtil.applyDeadband(m_driverController.getLeftY(), OIConstants.kDriveDeadband),
-MathUtil.applyDeadband(m_driverController.getLeftX(), OIConstants.kDriveDeadband),
-MathUtil.applyDeadband(m_driverController.getRightX(), OIConstants.kDriveDeadband),
true, true),
true),
m_robotDrive));
}

Expand Down Expand Up @@ -117,6 +117,6 @@ public Command getAutonomousCommand() {
m_robotDrive.resetOdometry(exampleTrajectory.getInitialPose());

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

0 comments on commit 7f7c62c

Please sign in to comment.