Skip to content

Commit 00eb862

Browse files
committed
Merge branch 'wpilib-2025' into develop
1 parent a109236 commit 00eb862

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

63 files changed

+5377
-3753
lines changed

.wpilib/wpilib_preferences.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
{
22
"enableCppIntellisense": false,
33
"currentLanguage": "java",
4-
"projectYear": "2024"
4+
"projectYear": "2025beta"
55
}

README.md

Lines changed: 60 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44

55
Custom library for 418 Purple Haze
66

7-
Note: CTRE will not be as well supported as REV products as our team primarily lives in the REV Robotics ecosystem
87

98
## Features
109
* Hardware wrappers with built-in AdvantageKit logging
@@ -18,8 +17,10 @@ Note: CTRE will not be as well supported as REV products as our team primarily l
1817
* More accurate velocity readings
1918
* CTRE
2019
* CANivore
20+
* Use of CANivore is HIGHLY recommended, as adjustment of status frame rates isn't easily possible while protecting the underlying sensor getter methods.
2121
* Pigeon 2.0
22-
* CANCoder
22+
* CANcoder
23+
* TalonFX
2324
* VictorSPX
2425
* TalonSRX
2526
* Kauai Labs
@@ -29,19 +30,32 @@ Note: CTRE will not be as well supported as REV products as our team primarily l
2930
* Field centric and robot centric velocity readings
3031
* Redux Robotics
3132
* Canandgyro
33+
* ThriftyBot
34+
* ThriftyNova
3235
* Generic
3336
* Analog sensor
3437
* Compressor
3538
* Single and double solenoid
3639
* Limit switch
3740
* Servo
38-
* MAXSwerve module support
39-
* Supports NEO v1.0/1.1 or NEO Vortex + NEO 550 configuration only
40-
* REV through bore encoder must be used
41-
* Module must be calibrated using [REV MAXSwerve calibration tool](https://docs.revrobotics.com/sparkmax/software-resources/calibration-for-maxswerve)
42-
* Robot rotation PID
43-
* Traction control
44-
* Swerve second order kinematics correction
41+
* Swerve module support with both REV and CTRE motor controllers
42+
* Supported modules:
43+
* REV MAXSwerve (REV Spark only)
44+
* SDS MK4/MK4i/MK4c
45+
* WCP Swerve X/Xi/X2
46+
* TTB Swerve
47+
* Support for custom or other modules can be added easily!
48+
* Module must be calibrated using calibration tool provided by module manufacturer
49+
* Mixing motor controller vendors within a module is NOT supported (ex. TalonFX for drive, Spark Max for rotation)
50+
* More info [here](src/main/java/org/lasarobotics/drive/swerve/README.md)
51+
* Swerve drive parent class
52+
* Robot rotation PID
53+
* Automatic module "locking"
54+
* Traction control
55+
* Swerve second order kinematics correction
56+
* More info [here](src/main/java/org/lasarobotics/drive/swerve/README.md)
57+
* Health monitoring and automatic recovery
58+
* Available in the hardware wrappers and for subsystems
4559
* Configurable input maps
4660
* LED strip support
4761
* JSON read/write
@@ -53,11 +67,11 @@ Note: CTRE will not be as well supported as REV products as our team primarily l
5367
### Required dependencies
5468
* AdvantageKit - https://github.com/Mechanical-Advantage/AdvantageKit/blob/main/docs/INSTALLATION.md
5569
* URCL - https://raw.githubusercontent.com/Mechanical-Advantage/URCL/maven/URCL.json
56-
* NavX - https://dev.studica.com/releases/2024/NavX.json
57-
* REVLib - https://software-metadata.revrobotics.com/REVLib-2024.json
58-
* ReduxLib - https://frcsdk.reduxrobotics.com/ReduxLib_2024.json
59-
* CTRE Phoenix5 - https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json
60-
* CTRE Phoenix6 - https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json
70+
* NavX - https://dev.studica.com/releases/2025/Studica-2025.1.1-alpha-14.json
71+
* REVLib - https://software-metadata.revrobotics.com/REVLib-2025.json
72+
* ReduxLib - https://frcsdk.reduxrobotics.com/ReduxLib_2025.json
73+
* CTRE Phoenix5 - https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-latest.json
74+
* CTRE Phoenix6 - https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json
6175
* PhotonLib - https://maven.photonvision.org/repository/internal/org/photonvision/photonlib-json/1.0/photonlib-json-1.0.json
6276

6377
### Online installation
@@ -85,6 +99,38 @@ dependencies {
8599
```
86100
Change the file path as needed.
87101

102+
## Robot project integration
103+
104+
1. Follow AdvantageKit setup instructions, and make your main `Robot.java` class extend `LoggedRobot`.
105+
2. In your `build.gradle` add the following:
106+
* To the `plugins` section: `id "com.peterabeles.gversion" version "1.10"`
107+
* Paste this before the `deploy` section:
108+
```
109+
project.compileJava.dependsOn(createVersionFile)
110+
gversion {
111+
srcDir = "src/main/java/"
112+
classPackage = "frc.robot"
113+
className = "BuildConstants"
114+
dateFormat = "yyyy-MM-dd HH:mm:ss z"
115+
timeZone = "America/Chicago" // Use preferred time zone
116+
indent = " "
117+
}
118+
```
119+
120+
3. In your `Robot.java` constructor, initialize the `PurpleManager`.
121+
```
122+
PurpleManager.initialize(
123+
this,
124+
AprilTagFieldLayout.loadField(AprilTagFields.k2024Crescendo),
125+
Path.of("/media/sda1"),
126+
BuildConstants.MAVEN_NAME,
127+
BuildConstants.GIT_SHA,
128+
BuildConstants.BUILD_DATE,
129+
true
130+
);
131+
```
132+
4. Call `PurpleManager.update()` in the beginning of the `robotPeriodic()` method of `Robot.java`.
133+
88134
## Releasing
89135
Create a release in GitHub. JitPack does the rest.
90136

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
plugins {
22
id "java-library"
33
id "maven-publish"
4-
id "edu.wpi.first.GradleRIO" version "2024.3.2"
4+
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
55
id "edu.wpi.first.WpilibTools" version "1.3.0"
66
}
77

src/main/java/com/revrobotics/SparkHelpers.java

Lines changed: 0 additions & 97 deletions
This file was deleted.
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
// Copyright (c) LASA Robotics and other contributors
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the MIT license file in the root directory of this project.
4+
5+
package com.revrobotics.spark;
6+
7+
/** Spark helpers */
8+
public class SparkHelpers {
9+
10+
public enum SparkModel {
11+
SparkMax(0),
12+
SparkFlex(1),
13+
Unknown(255);
14+
15+
final int id;
16+
17+
SparkModel(int id) {
18+
this.id = id;
19+
}
20+
21+
static SparkModel fromId(int id) {
22+
for (SparkModel model : values()) {
23+
if (model.id == id) return model;
24+
}
25+
return Unknown;
26+
}
27+
}
28+
/**
29+
* Enable mode which sets the output of the PID controllers to be voltage instead of duty cycle.
30+
*
31+
* <p>To disable, change or disable voltage compensation. Those settings will overwrite this one
32+
*/
33+
// public static REVLibError enablePIDVoltageOutput(CANSparkBase spark) {
34+
// return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_SetParameterUint32(spark.sparkMaxHandle, 74, 1));
35+
// }
36+
37+
/**
38+
* Get model of Spark
39+
* @param spark Spark to get model of
40+
* @return Model of Spark
41+
*/
42+
public static SparkModel getSparkModel(SparkBase spark) {
43+
switch (spark.getSparkModel()) {
44+
case SparkFlex:
45+
return SparkModel.SparkFlex;
46+
case SparkMax:
47+
return SparkModel.SparkMax;
48+
default:
49+
return SparkModel.Unknown;
50+
}
51+
}
52+
53+
public static long getSparkHandle(SparkBase spark) {
54+
return spark.sparkHandle;
55+
}
56+
}

src/main/java/org/lasarobotics/drive/RotatePIDController.java

Lines changed: 24 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -7,26 +7,27 @@
77
import java.util.HashMap;
88

99
import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction;
10-
import org.lasarobotics.utils.GlobalConstants;
1110
import org.lasarobotics.utils.PIDConstants;
1211

1312
import edu.wpi.first.math.MathUtil;
1413
import edu.wpi.first.math.controller.PIDController;
15-
import edu.wpi.first.units.Angle;
16-
import edu.wpi.first.units.Measure;
1714
import edu.wpi.first.units.Units;
18-
import edu.wpi.first.units.Velocity;
15+
import edu.wpi.first.units.measure.Angle;
16+
import edu.wpi.first.units.measure.AngularVelocity;
17+
import edu.wpi.first.units.measure.Dimensionless;
18+
import edu.wpi.first.units.measure.Time;
1919

2020
/** Rotate PID controller */
2121
public class RotatePIDController {
2222
private final double MIN_DEADBAND = 0.001;
2323
private final double MAX_DEADBAND = 0.2;
2424
private final double FILTER_FACTOR = 1.0 / 3.0;
25+
private final Time MAX_LOOKAHEAD = Units.Seconds.of(2);
2526

2627
private HashMap<Double, Double> m_rotateInputMap = new HashMap<Double, Double>();
2728
private PIDController m_pidController;
28-
private double m_rotateScalar;
29-
private double m_lookAhead;
29+
private Angle m_rotateScalar;
30+
private Time m_lookAhead;
3031
private double m_deadband;
3132
private double m_rotateRequest;
3233
private boolean m_isRotating;
@@ -35,17 +36,24 @@ public class RotatePIDController {
3536
* Create an instance of RotatePIDController
3637
* @param rotateInputCurve Rotate input curve
3738
* @param pidf PID constants
38-
* @param rotateScalar Value to turn input by (degrees)
39+
* @param rotateScalar Value to scale rotate input by
3940
* @param deadband Controller deadband
4041
* @param lookAhead Number of loops to look ahead by
4142
*/
42-
public RotatePIDController(PolynomialSplineFunction rotateInputCurve, PIDConstants pidf, double rotateScalar, double deadband, double lookAhead) {
43-
this.m_pidController = new PIDController(pidf.kP, 0.0, pidf.kD, pidf.period);
43+
public RotatePIDController(PolynomialSplineFunction rotateInputCurve,
44+
PIDConstants pidf,
45+
Angle rotateScalar,
46+
Dimensionless deadband,
47+
Time lookAhead) {
48+
this.m_pidController = new PIDController(pidf.kP, 0.0, pidf.kD, pidf.period.in(Units.Seconds));
4449
this.m_rotateScalar = rotateScalar;
45-
this.m_deadband = MathUtil.clamp(deadband, MIN_DEADBAND, MAX_DEADBAND);
46-
this.m_lookAhead = lookAhead;
50+
this.m_deadband = MathUtil.clamp(deadband.in(Units.Percent), MIN_DEADBAND, MAX_DEADBAND);
51+
this.m_lookAhead = Units.Seconds.of(MathUtil.clamp(lookAhead.in(Units.Seconds), 0.0, MAX_LOOKAHEAD.in(Units.Seconds)));
4752
this.m_isRotating = false;
4853

54+
// Enable PID position wrapping
55+
m_pidController.enableContinuousInput(0.0, 360.0);
56+
4957
// Fill turn input hashmap
5058
for (int i = 0; i <= 1000; i++) {
5159
double key = (double)i / 1000;
@@ -66,7 +74,7 @@ public RotatePIDController(PolynomialSplineFunction rotateInputCurve, PIDConstan
6674
*
6775
* @return Optimal rotate output
6876
*/
69-
public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<Velocity<Angle>> rotateRate, double rotateRequest) {
77+
public AngularVelocity calculate(Angle currentAngle, AngularVelocity rotateRate, double rotateRequest) {
7078
// Filter rotate request
7179
m_rotateRequest -= (m_rotateRequest - rotateRequest) * FILTER_FACTOR;
7280

@@ -76,12 +84,12 @@ public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<V
7684
m_rotateRequest = Math.copySign(Math.floor(Math.abs(m_rotateRequest) * 1000) / 1000, m_rotateRequest) + 0.0;
7785
double scaledTurnRequest = m_rotateInputMap.get(m_rotateRequest);
7886
// Add delta to setpoint scaled by factor
79-
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (scaledTurnRequest * m_rotateScalar));
87+
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + m_rotateScalar.times(scaledTurnRequest).in(Units.Degrees));
8088
m_isRotating = true;
8189
} else {
8290
// When rotation is complete, set setpoint to current angle
8391
if (m_isRotating) {
84-
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (rotateRate.in(Units.DegreesPerSecond) * m_lookAhead * GlobalConstants.ROBOT_LOOP_PERIOD));
92+
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (rotateRate.in(Units.DegreesPerSecond) * m_lookAhead.in(Units.Seconds)));
8593
m_isRotating = false;
8694
}
8795
}
@@ -94,15 +102,15 @@ public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<V
94102
* @param positionTolerance Position error that is tolerable
95103
* @param velocityTolerance Velocity error that is tolerable
96104
*/
97-
public void setTolerance(Measure<Angle> positionTolerance, Measure<Velocity<Angle>> velocityTolerance) {
105+
public void setTolerance(Angle positionTolerance, AngularVelocity velocityTolerance) {
98106
m_pidController.setTolerance(positionTolerance.in(Units.Degrees), velocityTolerance.in(Units.DegreesPerSecond));
99107
}
100108

101109
/**
102110
* Set setpoint of rotation PID controller
103111
* @param angle
104112
*/
105-
public void setSetpoint(Measure<Angle> angle) {
113+
public void setSetpoint(Angle angle) {
106114
m_pidController.setSetpoint(angle.in(Units.Degrees));
107115
}
108116

0 commit comments

Comments
 (0)