Skip to content

Commit

Permalink
Merge branch 'wpilib-2025' into develop
Browse files Browse the repository at this point in the history
  • Loading branch information
viggy96 committed Dec 25, 2024
1 parent a109236 commit 00eb862
Show file tree
Hide file tree
Showing 63 changed files with 5,377 additions and 3,753 deletions.
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
{
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024"
"projectYear": "2025beta"
}
74 changes: 60 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

Custom library for 418 Purple Haze

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

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

### Online installation
Expand Down Expand Up @@ -85,6 +99,38 @@ dependencies {
```
Change the file path as needed.

## Robot project integration

1. Follow AdvantageKit setup instructions, and make your main `Robot.java` class extend `LoggedRobot`.
2. In your `build.gradle` add the following:
* To the `plugins` section: `id "com.peterabeles.gversion" version "1.10"`
* Paste this before the `deploy` section:
```
project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "frc.robot"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/Chicago" // Use preferred time zone
indent = " "
}
```

3. In your `Robot.java` constructor, initialize the `PurpleManager`.
```
PurpleManager.initialize(
this,
AprilTagFieldLayout.loadField(AprilTagFields.k2024Crescendo),
Path.of("/media/sda1"),
BuildConstants.MAVEN_NAME,
BuildConstants.GIT_SHA,
BuildConstants.BUILD_DATE,
true
);
```
4. Call `PurpleManager.update()` in the beginning of the `robotPeriodic()` method of `Robot.java`.

## Releasing
Create a release in GitHub. JitPack does the rest.

Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "java-library"
id "maven-publish"
id "edu.wpi.first.GradleRIO" version "2024.3.2"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
id "edu.wpi.first.WpilibTools" version "1.3.0"
}

Expand Down
97 changes: 0 additions & 97 deletions src/main/java/com/revrobotics/SparkHelpers.java

This file was deleted.

56 changes: 56 additions & 0 deletions src/main/java/com/revrobotics/spark/SparkHelpers.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright (c) LASA Robotics and other contributors
// Open Source Software; you can modify and/or share it under the terms of
// the MIT license file in the root directory of this project.

package com.revrobotics.spark;

/** Spark helpers */
public class SparkHelpers {

public enum SparkModel {
SparkMax(0),
SparkFlex(1),
Unknown(255);

final int id;

SparkModel(int id) {
this.id = id;
}

static SparkModel fromId(int id) {
for (SparkModel model : values()) {
if (model.id == id) return model;
}
return Unknown;
}
}
/**
* Enable mode which sets the output of the PID controllers to be voltage instead of duty cycle.
*
* <p>To disable, change or disable voltage compensation. Those settings will overwrite this one
*/
// public static REVLibError enablePIDVoltageOutput(CANSparkBase spark) {
// return REVLibError.fromInt(CANSparkMaxJNI.c_SparkMax_SetParameterUint32(spark.sparkMaxHandle, 74, 1));
// }

/**
* Get model of Spark
* @param spark Spark to get model of
* @return Model of Spark
*/
public static SparkModel getSparkModel(SparkBase spark) {
switch (spark.getSparkModel()) {
case SparkFlex:
return SparkModel.SparkFlex;
case SparkMax:
return SparkModel.SparkMax;
default:
return SparkModel.Unknown;
}
}

public static long getSparkHandle(SparkBase spark) {
return spark.sparkHandle;
}
}
40 changes: 24 additions & 16 deletions src/main/java/org/lasarobotics/drive/RotatePIDController.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,26 +7,27 @@
import java.util.HashMap;

import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction;
import org.lasarobotics.utils.GlobalConstants;
import org.lasarobotics.utils.PIDConstants;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Units;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Dimensionless;
import edu.wpi.first.units.measure.Time;

/** Rotate PID controller */
public class RotatePIDController {
private final double MIN_DEADBAND = 0.001;
private final double MAX_DEADBAND = 0.2;
private final double FILTER_FACTOR = 1.0 / 3.0;
private final Time MAX_LOOKAHEAD = Units.Seconds.of(2);

private HashMap<Double, Double> m_rotateInputMap = new HashMap<Double, Double>();
private PIDController m_pidController;
private double m_rotateScalar;
private double m_lookAhead;
private Angle m_rotateScalar;
private Time m_lookAhead;
private double m_deadband;
private double m_rotateRequest;
private boolean m_isRotating;
Expand All @@ -35,17 +36,24 @@ public class RotatePIDController {
* Create an instance of RotatePIDController
* @param rotateInputCurve Rotate input curve
* @param pidf PID constants
* @param rotateScalar Value to turn input by (degrees)
* @param rotateScalar Value to scale rotate input by
* @param deadband Controller deadband
* @param lookAhead Number of loops to look ahead by
*/
public RotatePIDController(PolynomialSplineFunction rotateInputCurve, PIDConstants pidf, double rotateScalar, double deadband, double lookAhead) {
this.m_pidController = new PIDController(pidf.kP, 0.0, pidf.kD, pidf.period);
public RotatePIDController(PolynomialSplineFunction rotateInputCurve,
PIDConstants pidf,
Angle rotateScalar,
Dimensionless deadband,
Time lookAhead) {
this.m_pidController = new PIDController(pidf.kP, 0.0, pidf.kD, pidf.period.in(Units.Seconds));
this.m_rotateScalar = rotateScalar;
this.m_deadband = MathUtil.clamp(deadband, MIN_DEADBAND, MAX_DEADBAND);
this.m_lookAhead = lookAhead;
this.m_deadband = MathUtil.clamp(deadband.in(Units.Percent), MIN_DEADBAND, MAX_DEADBAND);
this.m_lookAhead = Units.Seconds.of(MathUtil.clamp(lookAhead.in(Units.Seconds), 0.0, MAX_LOOKAHEAD.in(Units.Seconds)));
this.m_isRotating = false;

// Enable PID position wrapping
m_pidController.enableContinuousInput(0.0, 360.0);

// Fill turn input hashmap
for (int i = 0; i <= 1000; i++) {
double key = (double)i / 1000;
Expand All @@ -66,7 +74,7 @@ public RotatePIDController(PolynomialSplineFunction rotateInputCurve, PIDConstan
*
* @return Optimal rotate output
*/
public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<Velocity<Angle>> rotateRate, double rotateRequest) {
public AngularVelocity calculate(Angle currentAngle, AngularVelocity rotateRate, double rotateRequest) {
// Filter rotate request
m_rotateRequest -= (m_rotateRequest - rotateRequest) * FILTER_FACTOR;

Expand All @@ -76,12 +84,12 @@ public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<V
m_rotateRequest = Math.copySign(Math.floor(Math.abs(m_rotateRequest) * 1000) / 1000, m_rotateRequest) + 0.0;
double scaledTurnRequest = m_rotateInputMap.get(m_rotateRequest);
// Add delta to setpoint scaled by factor
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (scaledTurnRequest * m_rotateScalar));
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + m_rotateScalar.times(scaledTurnRequest).in(Units.Degrees));
m_isRotating = true;
} else {
// When rotation is complete, set setpoint to current angle
if (m_isRotating) {
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (rotateRate.in(Units.DegreesPerSecond) * m_lookAhead * GlobalConstants.ROBOT_LOOP_PERIOD));
m_pidController.setSetpoint(currentAngle.in(Units.Degrees) + (rotateRate.in(Units.DegreesPerSecond) * m_lookAhead.in(Units.Seconds)));
m_isRotating = false;
}
}
Expand All @@ -94,15 +102,15 @@ public Measure<Velocity<Angle>> calculate(Measure<Angle> currentAngle, Measure<V
* @param positionTolerance Position error that is tolerable
* @param velocityTolerance Velocity error that is tolerable
*/
public void setTolerance(Measure<Angle> positionTolerance, Measure<Velocity<Angle>> velocityTolerance) {
public void setTolerance(Angle positionTolerance, AngularVelocity velocityTolerance) {
m_pidController.setTolerance(positionTolerance.in(Units.Degrees), velocityTolerance.in(Units.DegreesPerSecond));
}

/**
* Set setpoint of rotation PID controller
* @param angle
*/
public void setSetpoint(Measure<Angle> angle) {
public void setSetpoint(Angle angle) {
m_pidController.setSetpoint(angle.in(Units.Degrees));
}

Expand Down
Loading

0 comments on commit 00eb862

Please sign in to comment.