Skip to content

Commit

Permalink
updated wpilib and vendor library betas
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Dec 22, 2024
1 parent 55e9d39 commit 9260faa
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 21 deletions.
2 changes: 1 addition & 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 "2025.1.1-beta-2"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-3"
id 'com.diffplug.spotless' version '6.20.0'
}

Expand Down
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
import edu.wpi.first.epilogue.Epilogue;
import edu.wpi.first.epilogue.Logged;
import edu.wpi.first.epilogue.Logged.Strategy;
import edu.wpi.first.epilogue.logging.DataLogger;
import edu.wpi.first.epilogue.logging.FileLogger;
import edu.wpi.first.epilogue.logging.NTDataLogger;
import edu.wpi.first.epilogue.logging.EpilogueBackend;
import edu.wpi.first.epilogue.logging.FileBackend;
import edu.wpi.first.epilogue.logging.NTEpilogueBackend;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
Expand Down Expand Up @@ -98,15 +98,15 @@ private void setFileOnly(boolean fileOnly) {
DogLog.setOptions(DogLog.getOptions().withNtPublish(!fileOnly));

if (fileOnly) {
Epilogue.getConfig().dataLogger = new FileLogger(DataLogManager.getLog());
Epilogue.getConfig().backend = new FileBackend(DataLogManager.getLog());
return;
}

// if doing both file and nt logging, use the datalogger multilogger setup
Epilogue.getConfig().dataLogger =
DataLogger.multi(
new NTDataLogger(_ntInst), // TODO: watch out unit tests
new FileLogger(DataLogManager.getLog()));
Epilogue.getConfig().backend =
EpilogueBackend.multi(
new NTEpilogueBackend(_ntInst), // TODO: watch out unit tests
new FileBackend(DataLogManager.getLog()));
}

private void configureBindings() {
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -342,13 +342,17 @@ public void drive(double velX, double velY, double velOmega) {
ChassisSpeeds tempSpeeds = _driverChassisSpeeds;
SwerveModuleState[] tempStates;

if (_isFieldOriented) tempSpeeds.toRobotRelativeSpeeds(getHeading());
// TODO: this might be too many memory allocations

if (_isFieldOriented)
tempSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(tempSpeeds, getHeading());

tempStates = getKinematics().toSwerveModuleStates(tempSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(tempStates, SwerveConstants.maxTranslationalSpeed);
tempSpeeds = getKinematics().toChassisSpeeds(tempStates);

if (_isFieldOriented) tempSpeeds.toFieldRelativeSpeeds(getHeading());
if (_isFieldOriented)
tempSpeeds = ChassisSpeeds.fromRobotRelativeSpeeds(tempSpeeds, getHeading());

velX = tempSpeeds.vxMetersPerSecond;
velY = tempSpeeds.vyMetersPerSecond;
Expand Down
8 changes: 4 additions & 4 deletions src/test/java/frc/robot/RobotTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@

import dev.doglog.DogLog;
import edu.wpi.first.epilogue.Epilogue;
import edu.wpi.first.epilogue.logging.FileLogger;
import edu.wpi.first.epilogue.logging.MultiLogger;
import edu.wpi.first.epilogue.logging.FileBackend;
import edu.wpi.first.epilogue.logging.MultiBackend;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
import org.junit.jupiter.api.AfterEach;
Expand All @@ -31,7 +31,7 @@ public void close() throws Exception {
@Test
public void fmsFileOnly() {
// at the start should be both nt and file logging
assert Epilogue.getConfig().dataLogger instanceof MultiLogger; // multilogger setup
assert Epilogue.getConfig().backend instanceof MultiBackend; // multilogger setup
assert DogLog.getOptions().ntPublish();

DriverStationSim.setFmsAttached(true);
Expand All @@ -42,7 +42,7 @@ public void fmsFileOnly() {
_robot.robotPeriodic();

// once the fms connects, it should be file only
assert Epilogue.getConfig().dataLogger instanceof FileLogger;
assert Epilogue.getConfig().backend instanceof FileBackend;
assertFalse(DogLog.getOptions().ntPublish());
}
}
12 changes: 6 additions & 6 deletions vendordeps/photonlib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "photonlib.json",
"name": "photonlib",
"version": "v2025.0.0-beta-6",
"version": "v2025.0.0-beta-8",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
"frcYear": "2025",
"mavenUrls": [
Expand All @@ -13,7 +13,7 @@
{
"groupId": "org.photonvision",
"artifactId": "photontargeting-cpp",
"version": "v2025.0.0-beta-6",
"version": "v2025.0.0-beta-8",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
Expand All @@ -28,7 +28,7 @@
{
"groupId": "org.photonvision",
"artifactId": "photonlib-cpp",
"version": "v2025.0.0-beta-6",
"version": "v2025.0.0-beta-8",
"libName": "photonlib",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -43,7 +43,7 @@
{
"groupId": "org.photonvision",
"artifactId": "photontargeting-cpp",
"version": "v2025.0.0-beta-6",
"version": "v2025.0.0-beta-8",
"libName": "photontargeting",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -60,12 +60,12 @@
{
"groupId": "org.photonvision",
"artifactId": "photonlib-java",
"version": "v2025.0.0-beta-6"
"version": "v2025.0.0-beta-8"
},
{
"groupId": "org.photonvision",
"artifactId": "photontargeting-java",
"version": "v2025.0.0-beta-6"
"version": "v2025.0.0-beta-8"
}
]
}

0 comments on commit 9260faa

Please sign in to comment.