Skip to content

Commit

Permalink
Update to WPILib 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
viggy96 committed Nov 7, 2023
1 parent a71d34f commit 0d46aec
Show file tree
Hide file tree
Showing 13 changed files with 106 additions and 73 deletions.
18 changes: 10 additions & 8 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
plugins {
id 'java-library'
id 'maven-publish'
id "edu.wpi.first.GradleRIO" version "2023.4.3"
id 'edu.wpi.first.WpilibTools' version '1.3.0'
id "java-library"
id "maven-publish"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
id "edu.wpi.first.WpilibTools" version "1.3.0"
}

group = 'com.github.lasarobotics'
java {
sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
}

sourceCompatibility = JavaVersion.VERSION_11
targetCompatibility = JavaVersion.VERSION_11
group = 'com.github.lasarobotics'

repositories {
maven {
Expand Down Expand Up @@ -39,7 +41,7 @@ dependencies {

testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.+'

annotationProcessor 'org.littletonrobotics.akit.junction:junction-autolog:2.2.4'
annotationProcessor 'org.littletonrobotics.akit.junction:junction-autolog:3.0.0-beta-2'
}

test {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/org/lasarobotics/hardware/Analog.java
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ private void updateInputs() {
@Override
public void periodic() {
updateInputs();
Logger.getInstance().processInputs(m_id.name, m_inputs);
Logger.processInputs(m_id.name, m_inputs);
}

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/org/lasarobotics/hardware/DMAService.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public static DMAService getInstance() {

private void run() {
m_readStatus = m_dmaSample.update(m_dma, TIMEOUT);
Logger.getInstance().recordOutput(READ_STATUS_ENTRY, m_readStatus.name());
Logger.recordOutput(READ_STATUS_ENTRY, m_readStatus.name());
}

public void start() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/org/lasarobotics/hardware/LimitSwitch.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ private void updateInputs() {
@Override
public void periodic() {
updateInputs();
Logger.getInstance().processInputs(m_id.name, m_inputs);
Logger.processInputs(m_id.name, m_inputs);
}

/**
Expand Down
14 changes: 2 additions & 12 deletions src/main/java/org/lasarobotics/hardware/NavX2.java
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ private void updateInputs() {
@Override
public void periodic() {
updateInputs();
Logger.getInstance().processInputs(m_name, m_inputs);
Logger.processInputs(m_name, m_inputs);
}

/**
Expand All @@ -161,16 +161,6 @@ public NavX2InputsAutoLogged getInputs() {
return m_inputs;
}

/**
* Calibrate the gyro. It's important to make sure that the robot is
* not moving while the calibration is in progress, this is typically done
* when the robot is first turned on while it's sitting at rest before the
* match starts.
*/
public void calibrate() {
m_navx.calibrate();
}

/**
* Returns true if the sensor is currently performing automatic
* gyro/accelerometer calibration. Automatic calibration occurs when the
Expand Down Expand Up @@ -221,6 +211,6 @@ public double getSimAngle() {
*/
@Override
public void close() {
m_navx.close();
m_navx = null;
}
}
2 changes: 1 addition & 1 deletion src/main/java/org/lasarobotics/hardware/Servo.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ public Servo(Servo.ID id) {
}

private void logOutputs(double value) {
Logger.getInstance().recordOutput(m_id.name + VALUE_LOG_ENTRY, value);
Logger.recordOutput(m_id.name + VALUE_LOG_ENTRY, value);
}

@Override
Expand Down
59 changes: 29 additions & 30 deletions src/main/java/org/lasarobotics/hardware/SparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ public static class SparkMaxInputs {

private boolean m_isSmoothMotionEnabled = false;
private Timer m_motionTimer;
private TrapezoidProfile.State m_desiredState;
private Function<TrapezoidProfile.State, Double> m_feedforwardSupplier;

private TrapezoidProfile m_motionProfile;
Expand Down Expand Up @@ -114,6 +115,7 @@ public SparkMax(ID id, MotorType motorType, SparkPIDConfig config, FeedbackSenso

this.m_config = config;
this.m_motionTimer = new Timer();
this.m_desiredState = new TrapezoidProfile.State();
initializeSparkPID(m_config, feedbackSensor);
}

Expand All @@ -123,10 +125,10 @@ public SparkMax(ID id, MotorType motorType, SparkPIDConfig config, FeedbackSenso
* @param ctrl Control mode that was used
*/
private void logOutputs(double value, ControlType ctrl) {
Logger.getInstance().recordOutput(m_id.name + VALUE_LOG_ENTRY, value);
Logger.getInstance().recordOutput(m_id.name + MODE_LOG_ENTRY, ctrl.name());
Logger.getInstance().recordOutput(m_id.name + CURRENT_LOG_ENTRY, m_spark.getOutputCurrent());
Logger.getInstance().recordOutput(m_id.name + MOTION_LOG_ENTRY, m_isSmoothMotionEnabled);
Logger.recordOutput(m_id.name + VALUE_LOG_ENTRY, value);
Logger.recordOutput(m_id.name + MODE_LOG_ENTRY, ctrl.name());
Logger.recordOutput(m_id.name + CURRENT_LOG_ENTRY, m_spark.getOutputCurrent());
Logger.recordOutput(m_id.name + MOTION_LOG_ENTRY, m_isSmoothMotionEnabled);
}

/**
Expand Down Expand Up @@ -246,7 +248,23 @@ private void handleSmoothMotion() {
if (!m_isSmoothMotionEnabled) return;

m_isSmoothMotionEnabled = !isSmoothMotionFinished();
TrapezoidProfile.State motionProfileState = m_motionProfile.calculate(m_motionTimer.get());
TrapezoidProfile.State currentState;
switch (m_feedbackSensor) {
case NEO_ENCODER:
currentState = new TrapezoidProfile.State(getInputs().encoderPosition, getInputs().encoderVelocity);
break;
case ANALOG:
currentState = new TrapezoidProfile.State(getInputs().analogPosition, getInputs().analogVelocity);
break;
case THROUGH_BORE_ENCODER:
currentState = new TrapezoidProfile.State(getInputs().absoluteEncoderPosition, getInputs().absoluteEncoderVelocity);
break;
default:
currentState = new TrapezoidProfile.State(getInputs().encoderPosition, getInputs().encoderVelocity);
break;
}

TrapezoidProfile.State motionProfileState = m_motionProfile.calculate(m_motionTimer.get(), m_desiredState, currentState);
set(
motionProfileState.position,
ControlType.kPosition,
Expand All @@ -265,7 +283,7 @@ public void addToSimulation(DCMotor motor) {
@Override
public void periodic() {
updateInputs();
Logger.getInstance().processInputs(m_id.name, m_inputs);
Logger.processInputs(m_id.name, m_inputs);

handleSmoothMotion();
}
Expand Down Expand Up @@ -447,37 +465,18 @@ public void setVelocityConversionFactor(FeedbackSensor sensor, double factor) {
}

/**
* Start smooth motion
* Execute a smooth motion to desired position
* @param value The target value for the motor
* @param motionConstraint The constraints for the motor
* @param feedforwardSupplier Lambda function to calculate feed forward
*/
public void setSmoothMotion(double value, TrapezoidProfile.Constraints motionConstraint, Function<TrapezoidProfile.State, Double> feedforwardSupplier) {
public void smoothMotion(double value, TrapezoidProfile.Constraints motionConstraint, Function<TrapezoidProfile.State, Double> feedforwardSupplier) {
m_isSmoothMotionEnabled = true;
m_feedforwardSupplier = feedforwardSupplier;
m_motionConstraint = motionConstraint;

// Generate states
TrapezoidProfile.State desiredState = new TrapezoidProfile.State(value, 0.0);
TrapezoidProfile.State currentState;
switch (m_feedbackSensor) {
case NEO_ENCODER:
currentState = new TrapezoidProfile.State(getInputs().encoderPosition, getInputs().encoderVelocity);
break;
case ANALOG:
currentState = new TrapezoidProfile.State(getInputs().analogPosition, getInputs().analogVelocity);
break;
case THROUGH_BORE_ENCODER:
currentState = new TrapezoidProfile.State(getInputs().absoluteEncoderPosition, getInputs().absoluteEncoderVelocity);
break;
default:
currentState = new TrapezoidProfile.State(getInputs().encoderPosition, getInputs().encoderVelocity);
break;
}

// Generate motion profile
m_motionTimer.restart();
m_motionProfile = new TrapezoidProfile(m_motionConstraint, desiredState, currentState);
m_desiredState = new TrapezoidProfile.State(value, 0.0);
m_motionProfile = new TrapezoidProfile(m_motionConstraint);
m_motionTimer.reset();
}

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/org/lasarobotics/led/LEDStrip.java
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,7 @@ public void set(Pattern pattern, Section... sections) {

// Log patterns
for (Section section : sections)
Logger.getInstance().recordOutput(String.join("/", m_leds.getName(), section.name()), pattern.name());
Logger.recordOutput(String.join("/", m_leds.getName(), section.name()), pattern.name());
}

/**
Expand Down
11 changes: 6 additions & 5 deletions vendordeps/AdvantageKit.json
Original file line number Diff line number Diff line change
@@ -1,32 +1,33 @@
{
"fileName": "AdvantageKit.json",
"name": "AdvantageKit",
"version": "2.2.4",
"version": "3.0.0-beta-2",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2024",
"mavenUrls": [],
"jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json",
"javaDependencies": [
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "wpilib-shim",
"version": "2.2.4"
"version": "3.0.0-beta-2"
},
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "junction-core",
"version": "2.2.4"
"version": "3.0.0-beta-2"
},
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-api",
"version": "2.2.4"
"version": "3.0.0-beta-2"
}
],
"jniDependencies": [
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-wpilibio",
"version": "2.2.4",
"version": "3.0.0-beta-2",
"skipInvalidPlatforms": false,
"isJar": false,
"validPlatforms": [
Expand Down
15 changes: 8 additions & 7 deletions vendordeps/NavX.json
Original file line number Diff line number Diff line change
@@ -1,25 +1,26 @@
{
"fileName": "NavX.json",
"name": "KauaiLabs_navX_FRC",
"version": "2023.0.3",
"name": "NavX",
"version": "2024.0.1-beta-3",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2024",
"mavenUrls": [
"https://dev.studica.com/maven/release/2023/"
"https://dev.studica.com/maven/release/2024/"
],
"jsonUrl": "https://dev.studica.com/releases/2023/NavX.json",
"jsonUrl": "https://dev.studica.com/releases/2024/NavX.json",
"javaDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-java",
"version": "2023.0.3"
"version": "2024.0.1-beta-3"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-cpp",
"version": "2023.0.3",
"version": "2024.0.1-beta-3",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": false,
Expand All @@ -30,7 +31,7 @@
"linuxraspbian",
"linuxarm32",
"linuxarm64",
"linux86-64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
]
Expand Down
38 changes: 38 additions & 0 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.0.0-beta-4",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
"javaDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.0.0-beta-4"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.0.0-beta-4",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal",
"linuxathena",
"linuxarm32",
"linuxarm64"
]
}
]
}
13 changes: 7 additions & 6 deletions vendordeps/REVLib.json
Original file line number Diff line number Diff line change
@@ -1,24 +1,25 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2023.1.3",
"version": "2024.0.0",
"frcYear": "2024",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"https://maven.revrobotics.com/"
],
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json",
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2023.1.3"
"version": "2024.0.0"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2023.1.3",
"version": "2024.0.0",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
Expand All @@ -36,7 +37,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2023.1.3",
"version": "2024.0.0",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand All @@ -54,7 +55,7 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2023.1.3",
"version": "2024.0.0",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
1 change: 1 addition & 0 deletions vendordeps/WPILibNewCommands.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
"name": "WPILib-New-Commands",
"version": "1.0.0",
"uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266",
"frcYear": "2024",
"mavenUrls": [],
"jsonUrl": "",
"javaDependencies": [
Expand Down

0 comments on commit 0d46aec

Please sign in to comment.