Skip to content

Commit

Permalink
Downgrade to 2024 WPILib (#747)
Browse files Browse the repository at this point in the history
  • Loading branch information
mjansen4857 authored Sep 26, 2024
1 parent ff5e79d commit 8095ea2
Show file tree
Hide file tree
Showing 13 changed files with 65 additions and 55 deletions.
6 changes: 3 additions & 3 deletions .github/workflows/build-pplib-release.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ jobs:
- os: windows-2022
artifact-name: PPLib-Win64
os-name: windows
- os: macos-14
artifact-name: PPLib-macOS
os-name: macos
# - os: macos-14
# artifact-name: PPLib-macOS
# os-name: macos
name: "[PPLib] Build - ${{ matrix.artifact-name }}"
runs-on: ${{ matrix.os }}
steps:
Expand Down
8 changes: 5 additions & 3 deletions .github/workflows/pplib-ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -160,16 +160,18 @@ jobs:
path: pathplannerlib/build/allOutputs

build-host:
env:
MACOSX_DEPLOYMENT_TARGET: 13.3
strategy:
fail-fast: false
matrix:
include:
- os: windows-2022
artifact-name: PPLib-Win64
os-name: windows
- os: macos-14
artifact-name: PPLib-macOS
os-name: macos
# - os: macos-14
# artifact-name: PPLib-macOS
# os-name: macos
name: "[PPLib] Build - ${{ matrix.artifact-name }}"
needs: [formatting, test]
runs-on: ${{ matrix.os }}
Expand Down
28 changes: 14 additions & 14 deletions pathplannerlib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ plugins {
id 'java'
id 'google-test'
id 'edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin' version '2020.2'
id 'edu.wpi.first.NativeUtils' version '2025.1.0'
id 'edu.wpi.first.NativeUtils' version '2024.7.2'
id 'edu.wpi.first.GradleJni' version '1.1.0'
id 'edu.wpi.first.GradleVsCode' version '2.1.0'
id 'com.diffplug.spotless' version '6.11.0'
Expand All @@ -27,20 +27,20 @@ apply from: 'config.gradle'

// Apply Java configuration
dependencies {
implementation 'edu.wpi.first.cscore:cscore-java:2025.+'
implementation 'edu.wpi.first.cameraserver:cameraserver-java:2025.+'
implementation 'edu.wpi.first.ntcore:ntcore-java:2025.+'
implementation 'edu.wpi.first.wpilibj:wpilibj-java:2025.+'
implementation 'edu.wpi.first.wpiutil:wpiutil-java:2025.+'
implementation 'edu.wpi.first.wpimath:wpimath-java:2025.+'
implementation 'edu.wpi.first.wpilibNewCommands:wpilibNewCommands-java:2025.+'
implementation 'edu.wpi.first.wpiunits:wpiunits-java:2025.+'
implementation 'edu.wpi.first.hal:hal-java:2025.+'
implementation 'edu.wpi.first.cscore:cscore-java:2024.+'
implementation 'edu.wpi.first.cameraserver:cameraserver-java:2024.+'
implementation 'edu.wpi.first.ntcore:ntcore-java:2024.+'
implementation 'edu.wpi.first.wpilibj:wpilibj-java:2024.+'
implementation 'edu.wpi.first.wpiutil:wpiutil-java:2024.+'
implementation 'edu.wpi.first.wpimath:wpimath-java:2024.+'
implementation 'edu.wpi.first.wpilibNewCommands:wpilibNewCommands-java:2024.+'
implementation 'edu.wpi.first.wpiunits:wpiunits-java:2024.+'
implementation 'edu.wpi.first.hal:hal-java:2024.+'
implementation "org.ejml:ejml-simple:0.43.1"
implementation "com.fasterxml.jackson.core:jackson-annotations:2.15.2"
implementation "com.fasterxml.jackson.core:jackson-core:2.15.2"
implementation "com.fasterxml.jackson.core:jackson-databind:2.15.2"
implementation 'edu.wpi.first.thirdparty.frc2024.opencv:opencv-java:4.8.0-4'
implementation "com.fasterxml.jackson.core:jackson-annotations:2.12.4"
implementation "com.fasterxml.jackson.core:jackson-core:2.12.4"
implementation "com.fasterxml.jackson.core:jackson-databind:2.12.4"
implementation 'edu.wpi.first.thirdparty.frc2024.opencv:opencv-java:4.8.0-2'

testImplementation 'org.junit.jupiter:junit-jupiter-api:5.9.0'
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.9.0'
Expand Down
4 changes: 2 additions & 2 deletions pathplannerlib/config.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@ nativeUtils.withCrossLinuxArm64()
nativeUtils {
wpi {
configureDependencies {
wpiVersion = "2025.+"
wpiVersion = "2024.+"
opencvYear = "frc2024"
googleTestYear = "frc2024"
niLibVersion = "2024.2.1"
opencvVersion = "4.8.0-4"
opencvVersion = "4.8.0-2"
googleTestVersion = "1.14.0-1"
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public FollowPathCommand(
throw new IllegalArgumentException(
"Events that are triggered during path following cannot require the drive subsystem");
}
addRequirements(eventReqs);
addRequirements(eventReqs.toArray(new Subsystem[0]));

this.path = this.originalPath;
// Ensure the ideal trajectory is generated
Expand Down Expand Up @@ -207,8 +207,8 @@ public static Command warmupCommand() {
new PathPlannerPath(
bezierPoints,
new PathConstraints(4.0, 4.0, 4.0, 4.0),
new IdealStartingState(0.0, Rotation2d.kZero),
new GoalEndState(0.0, Rotation2d.kCCW_90deg));
new IdealStartingState(0.0, new Rotation2d()),
new GoalEndState(0.0, Rotation2d.fromDegrees(90)));

return new FollowPathCommand(
path,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,9 @@ private static void generateStates(
state.pose =
new Pose2d(
state.pose.getTranslation(),
path.isReversed() ? (state.heading.plus(Rotation2d.k180deg)) : state.heading);
path.isReversed()
? (state.heading.plus(Rotation2d.fromDegrees(180)))
: state.heading);
}

if (i != 0) {
Expand Down Expand Up @@ -412,7 +414,7 @@ private static void reverseAccelPass(

Translation2d forceVec =
new Translation2d(
forceAtCarpet, state.moduleStates[m].fieldAngle.plus(Rotation2d.k180deg));
forceAtCarpet, state.moduleStates[m].fieldAngle.plus(Rotation2d.fromDegrees(180)));

// Add the module force vector to the robot force vector
linearForceVec = linearForceVec.plus(forceVec);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,19 +16,19 @@ public class PathPlannerTrajectoryState implements Interpolatable<PathPlannerTra
/** Field-relative chassis speeds at this state */
public ChassisSpeeds fieldSpeeds = new ChassisSpeeds();
/** Field-relative robot pose at this state */
public Pose2d pose = Pose2d.kZero;
public Pose2d pose = new Pose2d();
/** The linear velocity at this state in m/s */
public double linearVelocity = 0.0;
/** The torque current feedforward for each module's drive motor, in Amps. */
public double[] driveMotorTorqueCurrent;

// Values used only during generation, these will not be interpolated
/** The field-relative heading, or direction of travel, at this state */
protected Rotation2d heading = Rotation2d.kZero;
protected Rotation2d heading = new Rotation2d();
/** The distance between this state and the previous state */
protected double deltaPos = 0.0;
/** The difference in rotation between this state and the previous state */
protected Rotation2d deltaRot = Rotation2d.kZero;
protected Rotation2d deltaRot = new Rotation2d();
/**
* The {@link com.pathplanner.lib.trajectory.SwerveModuleTrajectoryState} states for this state
*/
Expand Down Expand Up @@ -85,11 +85,12 @@ public PathPlannerTrajectoryState reverse() {
reversed.timeSeconds = timeSeconds;
Translation2d reversedSpeeds =
new Translation2d(fieldSpeeds.vxMetersPerSecond, fieldSpeeds.vyMetersPerSecond)
.rotateBy(Rotation2d.k180deg);
.rotateBy(Rotation2d.fromDegrees(180));
reversed.fieldSpeeds =
new ChassisSpeeds(
reversedSpeeds.getX(), reversedSpeeds.getY(), fieldSpeeds.omegaRadiansPerSecond);
reversed.pose = new Pose2d(pose.getTranslation(), pose.getRotation().plus(Rotation2d.k180deg));
reversed.pose =
new Pose2d(pose.getTranslation(), pose.getRotation().plus(Rotation2d.fromDegrees(180)));
reversed.linearVelocity = -linearVelocity;
reversed.driveMotorTorqueCurrent = new double[driveMotorTorqueCurrent.length];
for (int m = 0; m < driveMotorTorqueCurrent.length; m++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@
/** Extension of a SwerveModuleState to include its field-relative position and angle */
public class SwerveModuleTrajectoryState extends SwerveModuleState {
/** Field relative angle of the swerve module */
protected Rotation2d fieldAngle = Rotation2d.kZero;
protected Rotation2d fieldAngle = new Rotation2d();
/** Position of this module on the field */
protected Translation2d fieldPos = Translation2d.kZero;
protected Translation2d fieldPos = new Translation2d();
/** Difference in module position between this state and the previous state */
protected double deltaPos = 0.0;
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,14 @@ PathPlannerAuto::PathPlannerAuto(std::string autoName) {
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/pathplanner/autos/" + autoName + ".auto";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!fileBuffer) {
if (!fileBuffer || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());
initFromJson(json);

AddRequirements(m_autoCommand->GetRequirements());
Expand All @@ -40,13 +41,14 @@ std::vector<std::shared_ptr<PathPlannerPath>> PathPlannerAuto::getPathGroupFromA
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/pathplanner/autos/" + autoName + ".auto";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!fileBuffer) {
if (!fileBuffer || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());
bool choreoAuto = json.contains("choreoAuto")
&& json.at("choreoAuto").get<bool>();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,15 @@ RobotConfig RobotConfig::fromGUISettings() {
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/pathplanner/settings.json";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!fileBuffer) {
if (!fileBuffer || error_code) {
throw FRC_MakeError(frc::err::Error,
"PathPlanner settings file could not be read");
}

wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());

bool isHolonomic = json.at("holonomicMode").get<bool>();
units::kilogram_t mass { json.at("robotMass").get<double>() };
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,13 +130,14 @@ std::shared_ptr<PathPlannerPath> PathPlannerPath::fromPathFile(
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/pathplanner/paths/" + pathName + ".path";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!fileBuffer) {
if (!fileBuffer || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());

std::shared_ptr < PathPlannerPath > path = PathPlannerPath::fromJson(json);
PPLibTelemetry::registerHotReloadPath(pathName, path);
Expand All @@ -155,13 +156,14 @@ std::shared_ptr<PathPlannerPath> PathPlannerPath::fromChoreoTrajectory(
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/choreo/" + trajectoryName + ".traj";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (!fileBuffer) {
if (!fileBuffer || error_code) {
throw std::runtime_error("Cannot open file: " + filePath);
}

wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());

std::vector < PathPlannerTrajectoryState > trajStates;
for (wpi::json::const_reference s : json.at("samples")) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ LocalADStar::LocalADStar() : fieldLength(16.54), fieldWidth(8.02), nodeSize(
const std::string filePath = frc::filesystem::GetDeployDirectory()
+ "/pathplanner/navgrid.json";

auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath);
std::error_code error_code;
auto fileBuffer = wpi::MemoryBuffer::GetFile(filePath, error_code);

if (fileBuffer) {
if (fileBuffer && !error_code) {
try {
wpi::json json = wpi::json::parse(
fileBuffer.value()->GetCharBuffer());
wpi::json json = wpi::json::parse(fileBuffer->GetCharBuffer());

nodeSize = json.at("nodeSizeMeters").get<double>();
wpi::json::const_reference grid = json.at("grid");
Expand Down
4 changes: 2 additions & 2 deletions pathplannerlib/vendordeps/WPILibNewCommands.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "WPILibNewCommands.json",
"name": "WPILib-New-Commands",
"version": "2025.+",
"version": "2024.+",
"uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266",
"mavenUrls": [],
"jsonUrl": "",
Expand All @@ -17,7 +17,7 @@
{
"groupId": "edu.wpi.first.wpilibNewCommands",
"artifactId": "wpilibNewCommands-cpp",
"version": "2025.+",
"version": "2024.+",
"libName": "wpilibNewCommands",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
Expand Down

0 comments on commit 8095ea2

Please sign in to comment.