diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 497bac00bc..08b06c91a1 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -20,48 +20,48 @@ jobs: steps: - uses: actions/checkout@v4 - uses: gradle/actions/wrapper-validation@v4 - build-examples: - - strategy: - fail-fast: false - matrix: - include: - - os: windows-2022 - architecture: x64 - - os: macos-14 - architecture: aarch64 - - os: ubuntu-22.04 - - name: "Photonlib - Build Examples - ${{ matrix.os }}" - runs-on: ${{ matrix.os }} - needs: [validation] - - steps: - - name: Checkout code - uses: actions/checkout@v4 - with: - fetch-depth: 0 - - name: Fetch tags - run: git fetch --tags --force - - name: Install Java 17 - uses: actions/setup-java@v4 - with: - java-version: 17 - distribution: temurin - - name: Install RoboRIO Toolchain - run: ./gradlew installRoboRioToolchain - # Need to publish to maven local first, so that C++ sim can pick it up - - name: Publish photonlib to maven local - run: ./gradlew photon-targeting:publishtomavenlocal photon-lib:publishtomavenlocal -x check - - name: Build Java examples - working-directory: photonlib-java-examples - run: ./gradlew build - - name: Build C++ examples - working-directory: photonlib-cpp-examples - run: ./gradlew build + # build-examples: + + # strategy: + # fail-fast: false + # matrix: + # include: + # - os: windows-2022 + # architecture: x64 + # - os: macos-14 + # architecture: aarch64 + # - os: ubuntu-24.04 + + # name: "Photonlib - Build Examples - ${{ matrix.os }}" + # runs-on: ${{ matrix.os }} + # needs: [validation] + + # steps: + # - name: Checkout code + # uses: actions/checkout@v4 + # with: + # fetch-depth: 0 + # - name: Fetch tags + # run: git fetch --tags --force + # - name: Install Java 17 + # uses: actions/setup-java@v4 + # with: + # java-version: 17 + # distribution: temurin + # - name: Install SystemCore Toolchain + # run: ./gradlew installSystemCoreToolchain + # # Need to publish to maven local first, so that C++ sim can pick it up + # - name: Publish photonlib to maven local + # run: ./gradlew photon-targeting:publishtomavenlocal photon-lib:publishtomavenlocal -x check + # - name: Build Java examples + # working-directory: photonlib-java-examples + # run: ./gradlew build + # - name: Build C++ examples + # working-directory: photonlib-cpp-examples + # run: ./gradlew build build-gradle: name: "Gradle Build" - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 needs: [validation] steps: # Checkout code. @@ -85,7 +85,7 @@ jobs: with: node-version: 22 - name: Install mrcal deps - run: sudo apt-get update && sudo apt-get install -y libcholmod3 liblapack3 libsuitesparseconfig5 + run: sudo add-apt-repository -y -S 'deb http://security.ubuntu.com/ubuntu jammy main universe' && sudo apt-get update && sudo apt-get install -y libcholmod3 liblapack3 libsuitesparseconfig5 - name: Gradle Build run: ./gradlew photon-targeting:build photon-core:build photon-server:build -x check - name: Gradle Tests @@ -94,7 +94,7 @@ jobs: run: ./gradlew jacocoTestReport build-offline-docs: name: "Build Offline Docs" - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 - uses: actions/setup-python@v5 @@ -121,7 +121,7 @@ jobs: build-photonlib-vendorjson: name: "Build Vendor JSON" - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 needs: [validation] steps: - uses: actions/checkout@v4 @@ -162,7 +162,7 @@ jobs: - os: macos-14 artifact-name: macOS architecture: aarch64 - - os: ubuntu-22.04 + - os: ubuntu-24.04 artifact-name: Linux name: "Photonlib - Build Host - ${{ matrix.artifact-name }}" @@ -185,7 +185,7 @@ jobs: name: Publish env: ARTIFACTORY_API_KEY: ${{ secrets.ARTIFACTORY_API_KEY }} - if: github.event_name == 'push' && github.repository_owner == 'photonvision' + if: github.event_name == 'push' && github.repository_owner == 'photonvision' && github.ref == 'refs/heads/main' # Copy artifacts to build/outputs/maven - run: ./gradlew photon-lib:publish photon-targeting:publish -PcopyOfflineArtifacts - uses: actions/upload-artifact@v4 @@ -198,17 +198,17 @@ jobs: fail-fast: false matrix: include: - - container: wpilib/roborio-cross-ubuntu:2025-24.04 - artifact-name: Athena - build-options: "-Ponlylinuxathena" - - container: wpilib/raspbian-cross-ubuntu:bullseye-22.04 + - container: wpilib/systemcore-cross-ubuntu:2025-24.04 + artifact-name: SystemCore + build-options: "-Ponlylinuxsystemcore" + - container: wpilib/raspbian-cross-ubuntu:bookworm-24.04 artifact-name: Raspbian build-options: "-Ponlylinuxarm32" - - container: wpilib/aarch64-cross-ubuntu:bullseye-22.04 + - container: wpilib/aarch64-cross-ubuntu:bookworm-24.04 artifact-name: Aarch64 build-options: "-Ponlylinuxarm64" - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 container: ${{ matrix.container }} name: "Photonlib - Build Docker - ${{ matrix.artifact-name }}" needs: [validation] @@ -226,7 +226,7 @@ jobs: run: ./gradlew photon-lib:publish photon-targeting:publish ${{ matrix.build-options }} env: ARTIFACTORY_API_KEY: ${{ secrets.ARTIFACTORY_API_KEY }} - if: github.event_name == 'push' && github.repository_owner == 'photonvision' + if: github.event_name == 'push' && github.repository_owner == 'photonvision' && github.ref == 'refs/heads/main' # Copy artifacts to build/outputs/maven - run: ./gradlew photon-lib:publish photon-targeting:publish -PcopyOfflineArtifacts ${{ matrix.build-options }} - uses: actions/upload-artifact@v4 @@ -237,7 +237,7 @@ jobs: combine: name: Combine needs: [build-photonlib-docker, build-photonlib-host] - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 with: @@ -278,11 +278,11 @@ jobs: artifact-name: macOSArm architecture: x64 arch-override: macarm64 - - os: ubuntu-22.04 + - os: ubuntu-24.04 artifact-name: Linux architecture: x64 arch-override: linuxx64 - - os: ubuntu-22.04 + - os: ubuntu-24.04 artifact-name: LinuxArm64 architecture: x64 arch-override: linuxarm64 @@ -337,7 +337,7 @@ jobs: fail-fast: false matrix: include: - - os: ubuntu-22.04 + - os: ubuntu-24.04 artifact-name: jar-Linux extraOpts: -Djdk.lang.Process.launchMechanism=vfork - os: windows-latest @@ -360,6 +360,7 @@ jobs: name: ${{ matrix.artifact-name }} # On linux, install mrcal packages - run: | + sudo add-apt-repository -y -S 'deb http://security.ubuntu.com/ubuntu jammy main universe' sudo apt-get update sudo apt-get install --yes libcholmod3 liblapack3 libsuitesparseconfig5 if: ${{ (matrix.os) == 'ubuntu-24.04' }} @@ -557,7 +558,7 @@ jobs: path: photonvision*.xz release: needs: [build-photonlib-vendorjson, build-package, build-image, build-rubik-image, combine] - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: # Download all fat JARs - uses: actions/download-artifact@v4 diff --git a/.github/workflows/lint-format.yml b/.github/workflows/lint-format.yml index 350bf38861..48b881a636 100644 --- a/.github/workflows/lint-format.yml +++ b/.github/workflows/lint-format.yml @@ -18,7 +18,7 @@ jobs: - uses: gradle/actions/wrapper-validation@v4 wpiformat: name: "wpiformat" - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 - name: Fetch all history and metadata @@ -47,7 +47,7 @@ jobs: javaformat: name: "Java Formatting" needs: [validation] - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 with: @@ -64,7 +64,7 @@ jobs: defaults: run: working-directory: photon-client - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 - name: Install pnpm diff --git a/.github/workflows/photon-api-docs.yml b/.github/workflows/photon-api-docs.yml index 9faad1f11d..fe8d77db50 100644 --- a/.github/workflows/photon-api-docs.yml +++ b/.github/workflows/photon-api-docs.yml @@ -27,7 +27,7 @@ jobs: defaults: run: working-directory: photon-client - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 - name: Install pnpm @@ -52,7 +52,7 @@ jobs: run_java_cpp_docs: name: Build Java and C++ API Docs needs: [validation] - runs-on: "ubuntu-22.04" + runs-on: "ubuntu-24.04" steps: - name: Checkout code uses: actions/checkout@v4 @@ -77,7 +77,7 @@ jobs: publish_api_docs: name: Publish API Docs needs: [run_java_cpp_docs] - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: # Download docs artifact - uses: actions/download-artifact@v4 @@ -104,7 +104,7 @@ jobs: publish_demo: name: Publish PhotonClient Demo needs: [build_demo] - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/download-artifact@v4 with: diff --git a/.github/workflows/photonvision-rtd.yml b/.github/workflows/photonvision-rtd.yml index 7f02b87c28..77b62de304 100644 --- a/.github/workflows/photonvision-rtd.yml +++ b/.github/workflows/photonvision-rtd.yml @@ -14,7 +14,7 @@ env: jobs: build: name: Build and Check Docs - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - uses: actions/checkout@v4 diff --git a/.github/workflows/python.yml b/.github/workflows/python.yml index 86dbb8fb93..ad9b9eb525 100644 --- a/.github/workflows/python.yml +++ b/.github/workflows/python.yml @@ -13,7 +13,7 @@ concurrency: jobs: buildAndDeploy: - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - name: Checkout code diff --git a/.gitignore b/.gitignore index 6416c2fba8..012ad3f618 100644 --- a/.gitignore +++ b/.gitignore @@ -147,4 +147,4 @@ photon-server/src/main/resources/web/* node_modules dist components.d.ts -photon-server/src/main/resources/web/index.html +/workspace diff --git a/.readthedocs.yaml b/.readthedocs.yaml index 4cf9063ec1..6f2f58d7bf 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -6,7 +6,7 @@ sphinx: fail_on_warning: true build: - os: ubuntu-22.04 + os: ubuntu-24.04 tools: python: "3.11" apt_packages: diff --git a/README.md b/README.md index 3008b0a856..3523b26b69 100644 --- a/README.md +++ b/README.md @@ -46,7 +46,7 @@ Note that these are case sensitive! - `-Pprofile`: enables JVM profiling - `-PwithSanitizers`: On Linux, enables `-fsanitize=address,undefined,leak` -If you're cross-compiling, you'll need the wpilib toolchain installed. This can be done via Gradle: for example `./gradlew installArm64Toolchain` or `./gradlew installRoboRioToolchain` +If you're cross-compiling, you'll need the wpilib toolchain installed. This can be done via Gradle: for example `./gradlew installArm64Toolchain` or `./gradlew installSystemCoreToolchain` ## Out-of-Source Dependencies diff --git a/build.gradle b/build.gradle index 1f0d90b7d8..8a77e649e1 100644 --- a/build.gradle +++ b/build.gradle @@ -3,8 +3,8 @@ import edu.wpi.first.toolchain.* plugins { id "cpp" id "com.diffplug.spotless" version "6.24.0" - id "edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin" version "2020.2" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin" version "2025.0" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" id 'edu.wpi.first.WpilibTools' version '1.3.0' id 'com.google.protobuf' version '0.9.3' apply false id 'edu.wpi.first.GradleJni' version '1.1.0' @@ -21,6 +21,7 @@ allprojects { maven { url = "https://maven.photonvision.org/snapshots" } maven { url = "https://jogamp.org/deployment/maven/" } } + wpilibRepositories.use2027Repos() wpilibRepositories.addAllReleaseRepositories(it) wpilibRepositories.addAllDevelopmentRepositories(it) } @@ -32,7 +33,7 @@ ext.allOutputsFolder = file("$project.buildDir/outputs") apply from: "versioningHelper.gradle" ext { - wpilibVersion = "2025.3.2" + wpilibVersion = "2027.0.0-alpha-2" wpimathVersion = wpilibVersion openCVYear = "2025" openCVversion = "4.10.0-3" @@ -40,7 +41,7 @@ ext { libcameraDriverVersion = "v2025.0.4" rknnVersion = "dev-v2025.0.0-5-g666c0c6" rubikVersion = "dev-v2025.1.0-8-g067a316" - frcYear = "2025" + frcYear = "2027_alpha1" mrcalVersion = "v2025.0.0"; diff --git a/docs/source/docs/hardware/selecting-hardware.md b/docs/source/docs/hardware/selecting-hardware.md index c04445b4d8..47189b512d 100644 --- a/docs/source/docs/hardware/selecting-hardware.md +++ b/docs/source/docs/hardware/selecting-hardware.md @@ -10,7 +10,7 @@ In order to use PhotonVision, you need a coprocessor and a camera. This page dis ### Minimum System Requirements -- Ubuntu 22.04 LTS or Windows 10/11 +- Ubuntu 24.04 LTS or Windows 10/11 - We don't recommend using Windows for anything except testing out the system on a local machine. - CPU: ARM Cortex-A53 (the CPU on Raspberry Pi 3) or better - At least 8GB of storage diff --git a/docs/source/docs/quick-start/common-setups.md b/docs/source/docs/quick-start/common-setups.md index 7d6ffaf602..dfd37e9f50 100644 --- a/docs/source/docs/quick-start/common-setups.md +++ b/docs/source/docs/quick-start/common-setups.md @@ -13,6 +13,11 @@ PhotonVision requires dedicated hardware, above and beyond a roboRIO. This page The Orange Pi 5 is the only currently supported device for object detection. ::: +## SystemCore Support + +The SystemCore is not supported by PhotonVision. PhotonVision is designed to utilize the entirety of the coprocessor's resources, and this could prove to be dangerous if attempted on the main robot controller. +There are no current plans to support running on SystemCore alongside robot code, and any attempts to do so are entirely at your own risk and will require a separate fork of PhotonVision. + ## SD Cards - 8GB or larger micro SD card diff --git a/photon-core/build.gradle b/photon-core/build.gradle index 6e9c99c1f1..4a8f06b670 100644 --- a/photon-core/build.gradle +++ b/photon-core/build.gradle @@ -22,6 +22,7 @@ dependencies { wpilibNatives wpilibTools.deps.wpilib("wpimath") wpilibNatives wpilibTools.deps.wpilib("wpinet") wpilibNatives wpilibTools.deps.wpilib("wpiutil") + wpilibNatives wpilibTools.deps.wpilib("datalog") wpilibNatives wpilibTools.deps.wpilib("ntcore") wpilibNatives wpilibTools.deps.wpilib("cscore") wpilibNatives wpilibTools.deps.wpilib("apriltag") diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java index a86cf51b18..32cc7b3067 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java @@ -354,7 +354,7 @@ private void setClientMode(NetworkConfig config) { ntInstance.stopClient(); String hostname = config.shouldManage ? config.hostname : CameraServerJNI.getHostname(); logger.debug("Starting NT Client with hostname: " + hostname); - ntInstance.startClient4(hostname); + ntInstance.startClient(hostname); try { int t = Integer.parseInt(config.ntServerAddress); if (!m_isRetryingConnection) logger.info("Starting NT Client, server team is " + t); diff --git a/photon-lib/build.gradle b/photon-lib/build.gradle index a06fc532e3..cb2b84945e 100644 --- a/photon-lib/build.gradle +++ b/photon-lib/build.gradle @@ -90,6 +90,7 @@ model { } } + nativeUtils.useRequiredLibrary(it, "datalog_shared") nativeUtils.useRequiredLibrary(it, "cscore_shared") nativeUtils.useRequiredLibrary(it, "cameraserver_shared") nativeUtils.useRequiredLibrary(it, "wpilib_executable_shared") @@ -369,6 +370,7 @@ dependencies { nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpimath") nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpinet") nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpiutil") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("datalog") nativeConfig.dependencies.add wpilibTools.deps.wpilib("ntcore") nativeConfig.dependencies.add wpilibTools.deps.wpilib("cscore") nativeConfig.dependencies.add wpilibTools.deps.wpilib("apriltag") diff --git a/photon-lib/src/generate/photonlib.json.in b/photon-lib/src/generate/photonlib.json.in index 5df9ae5d2c..a1a62268ea 100644 --- a/photon-lib/src/generate/photonlib.json.in +++ b/photon-lib/src/generate/photonlib.json.in @@ -18,7 +18,7 @@ "isJar": false, "validPlatforms": [ "windowsx86-64", - "linuxathena", + "linuxsystemcore", "linuxx86-64", "osxuniversal" ] @@ -35,7 +35,7 @@ "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "linuxathena", + "linuxsystemcore", "linuxx86-64", "osxuniversal" ] @@ -50,7 +50,7 @@ "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "linuxathena", + "linuxsystemcore", "linuxx86-64", "osxuniversal" ] diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index aa1fa0c53c..576629dcb5 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -24,7 +24,6 @@ package org.photonvision; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.MatBuilder; import edu.wpi.first.math.Matrix; @@ -163,8 +162,8 @@ public PhotonCamera(NetworkTableInstance instance, String cameraName) { new MultiSubscriber( instance, new String[] {"/photonvision/"}, PubSubOption.topicsOnly(true)); - HAL.report(tResourceType.kResourceType_PhotonCamera, InstanceCount); InstanceCount++; + HAL.reportUsage("PhotonVision/PhotonCamera", InstanceCount, ""); // HACK - start a TimeSyncServer, if we haven't yet. TimeSyncSingleton.load(); diff --git a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java index a9330f6102..f58de35289 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java @@ -26,7 +26,6 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.cscore.OpenCvLoader; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Pair; @@ -161,8 +160,8 @@ public PhotonPoseEstimator( OpenCvLoader.forceStaticLoad(); } - HAL.report(tResourceType.kResourceType_PhotonPoseEstimator, InstanceCount); InstanceCount++; + HAL.reportUsage("PhotonVision/PhotonPoseEstimator", InstanceCount, ""); } /** Invalidates the pose cache. */ diff --git a/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp b/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp index 6b7f67bc88..b6edf5c86d 100644 --- a/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp +++ b/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp @@ -24,7 +24,7 @@ #include "photon/PhotonCamera.h" -#include +#include #include #include @@ -208,8 +208,8 @@ PhotonCamera::PhotonCamera(nt::NetworkTableInstance instance, frc::Alert::AlertType::kWarning), timesyncAlert(PHOTON_ALERT_GROUP, "", frc::Alert::AlertType::kWarning) { verifyDependencies(); - HAL_Report(HALUsageReporting::kResourceType_PhotonCamera, InstanceCount); InstanceCount++; + HAL_ReportUsage("PhotonVision/PhotonCamera", InstanceCount, ""); // The Robot class is actually created here: // https://github.com/wpilibsuite/allwpilib/blob/811b1309683e930a1ce69fae818f943ff161b7a5/wpilibc/src/main/native/include/frc/RobotBase.h#L33 diff --git a/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp b/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp index 6903240c94..5b6ff47705 100644 --- a/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp +++ b/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp @@ -24,7 +24,7 @@ #include "photon/PhotonPoseEstimator.h" -#include +#include #include #include @@ -78,9 +78,8 @@ PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags, referencePose(frc::Pose3d()), poseCacheTimestamp(-1_s), headingBuffer(frc::TimeInterpolatableBuffer(1_s)) { - HAL_Report(HALUsageReporting::kResourceType_PhotonPoseEstimator, - InstanceCount); InstanceCount++; + HAL_ReportUsage("PhotonVision/PhotonPoseEstimator", InstanceCount, ""); } void PhotonPoseEstimator::SetMultiTagFallbackStrategy(PoseStrategy strategy) { diff --git a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java index 9a2f69dd42..c5ed3189b4 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java @@ -253,14 +253,14 @@ public void testRestartingRobotAndCoproc( if (i == coprocStart || i == coprocRestart) { coprocNt.setServer("127.0.0.1", 5940); - coprocNt.startClient4("testClient"); + coprocNt.startClient("testClient"); // PhotonCamera makes a server by default - connect to it tspClient = new TimeSyncClient("127.0.0.1", 5810, 0.5); } if (i == robotStart || i == robotRestart) { - robotNt.startServer("networktables_random.json", "", 5941, 5940); + robotNt.startServer("networktables_random.json", "", 5940); } Thread.sleep(100); diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java index 130bd25ba8..c5cad38645 100644 --- a/photon-server/src/main/java/org/photonvision/Main.java +++ b/photon-server/src/main/java/org/photonvision/Main.java @@ -165,7 +165,75 @@ private static void addTestModeSources() { VisionSourceManager.getInstance().registerLoadedConfigs(cameraConfigs); } + private static void serveDenialPage() { + String docsLink = + "https://docs.photonvision.org/en/latest/docs/quick-start/common-setups.html#systemcore-support"; + + logger.error( + "SystemCore is not a supported platform for PhotonVision!\n " + + "Please visit " + + docsLink + + " for more information."); + + try { + int port = 5800; + io.javalin.Javalin app = null; + try { + app = io.javalin.Javalin.create(cfg -> cfg.showJavalinBanner = false).start(port); + } catch (Exception e) { + logger.warn("Failed to bind to port 5800, exiting: " + e.getMessage()); + port = DEFAULT_WEBPORT; + app = io.javalin.Javalin.create(cfg -> cfg.showJavalinBanner = false).start(port); + } + + final int boundPort = port; + final String html = + "" + + "Unsupported platform" + + "

Main Robot Controllers shouldn't run PhotonVision, but yours does! " + + "Please uninstall PhotonVision. " + + "If you choose to modify PhotonVision so that it functions on SystemCore, " + + "you do so entirely at your own risk and without any support. " + + "For more information, see " + + docsLink + + ".

"; + + app.get( + "/", + ctx -> { + ctx.contentType("text/html; charset=utf-8"); + ctx.result(html); + }); + + logger.info( + "Served SystemCore warning page on port " + + boundPort + + " - process will remain running to serve the page."); + + // Prevent main from exiting so the page remains available. + final Object lock = new Object(); + synchronized (lock) { + try { + lock.wait(); + } catch (InterruptedException ignored) { + } + } + } catch (Exception e) { + logger.error("Failed to start static warning page server", e); + } + + // Exit + System.exit(1); + } + public static void main(String[] args) { + if (Platform.isSystemCore()) { + serveDenialPage(); + } + logger.info( "Starting PhotonVision version " + PhotonVersion.versionString diff --git a/photon-targeting/build.gradle b/photon-targeting/build.gradle index eef9fa9a08..cddd4af8f6 100644 --- a/photon-targeting/build.gradle +++ b/photon-targeting/build.gradle @@ -55,6 +55,7 @@ model { } nativeUtils.useRequiredLibrary(it, "wpiutil_shared") + nativeUtils.useRequiredLibrary(it, "datalog_shared") nativeUtils.useRequiredLibrary(it, "wpimath_shared") nativeUtils.useRequiredLibrary(it, "wpinet_shared") nativeUtils.useRequiredLibrary(it, "ntcore_shared") @@ -65,7 +66,7 @@ model { enableCheckTask project.hasProperty('doJniCheck') javaCompileTasks << compileJava - jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.roborio) + jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.systemcore) jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm32) jniCrossCompileOptions << JniCrossCompileOptions(nativeUtils.wpi.platforms.linuxarm64) @@ -83,6 +84,7 @@ model { } nativeUtils.useRequiredLibrary(it, "wpiutil_shared") + nativeUtils.useRequiredLibrary(it, "datalog_shared") nativeUtils.useRequiredLibrary(it, "wpimath_shared") nativeUtils.useRequiredLibrary(it, "wpinet_shared") nativeUtils.useRequiredLibrary(it, "ntcore_shared") @@ -134,6 +136,7 @@ model { nativeUtils.useRequiredLibrary(it, "wpilib_executable_shared") nativeUtils.useRequiredLibrary(it, "googletest_static") + nativeUtils.useRequiredLibrary(it, "datalog_shared") nativeUtils.useRequiredLibrary(it, "apriltag_shared") nativeUtils.useRequiredLibrary(it, "cscore_shared") nativeUtils.useRequiredLibrary(it, "opencv_shared") @@ -193,6 +196,7 @@ def nativeTasks = wpilibTools.createExtractionTasks { nativeTasks.addToSourceSetResources(sourceSets.test) nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpiutil") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("datalog") nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpimath") nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpinet") nativeConfig.dependencies.add wpilibTools.deps.wpilib("ntcore") diff --git a/photon-targeting/src/main/java/org/photonvision/common/hardware/Platform.java b/photon-targeting/src/main/java/org/photonvision/common/hardware/Platform.java index 485ec701e2..9f6998fc82 100644 --- a/photon-targeting/src/main/java/org/photonvision/common/hardware/Platform.java +++ b/photon-targeting/src/main/java/org/photonvision/common/hardware/Platform.java @@ -44,6 +44,13 @@ public enum Platform { true, OSType.LINUX, true), // Raspberry Pi 3/4 with a 64-bit image + LINUX_SYSTEMCORE( + "Linux Systemcore 64-bit NOT SUPPORTED", + Platform::getUnknownModel, + "linuxarm64", + false, + OSType.LINUX, + false), // SystemCore 64-bit LINUX_RK3588_64( "Linux AARCH 64-bit with RK3588", Platform::getLinuxDeviceTreeModel, @@ -127,6 +134,11 @@ public static boolean isLinux() { return currentPlatform.osType == OSType.LINUX; } + public static boolean isSystemCore() { + File sysCore = new File("/home/systemcore"); + return sysCore.exists() | fileHasText("/etc/os-release", "systemcore"); + } + public static boolean isRK3588() { return Platform.isOrangePi() || Platform.isCoolPi4b() || Platform.isRock5C(); } @@ -205,7 +217,9 @@ public static Platform getCurrentPlatform() { } if (OS_NAME.startsWith("Linux")) { - if (isPiSBC()) { + if (isSystemCore()) { + return LINUX_SYSTEMCORE; + } else if (isPiSBC()) { if (OS_ARCH.equals("arm") || OS_ARCH.equals("arm32")) { return LINUX_RASPBIAN32; } else if (OS_ARCH.equals("aarch64") || OS_ARCH.equals("arm64")) { diff --git a/photon-targeting/src/main/java/org/photonvision/jni/LibraryLoader.java b/photon-targeting/src/main/java/org/photonvision/jni/LibraryLoader.java index 0572711fde..47e455a514 100644 --- a/photon-targeting/src/main/java/org/photonvision/jni/LibraryLoader.java +++ b/photon-targeting/src/main/java/org/photonvision/jni/LibraryLoader.java @@ -20,6 +20,7 @@ import edu.wpi.first.apriltag.jni.AprilTagJNI; import edu.wpi.first.cscore.CameraServerJNI; import edu.wpi.first.cscore.OpenCvLoader; +import edu.wpi.first.datalog.DataLogJNI; import edu.wpi.first.hal.JNIWrapper; import edu.wpi.first.math.jni.WPIMathJNI; import edu.wpi.first.net.WPINetJNI; @@ -38,6 +39,7 @@ public static boolean loadWpiLibraries() { NetworkTablesJNI.Helper.setExtractOnStaticLoad(false); WPIUtilJNI.Helper.setExtractOnStaticLoad(false); + DataLogJNI.Helper.setExtractOnStaticLoad(false); CameraServerJNI.Helper.setExtractOnStaticLoad(false); OpenCvLoader.Helper.setExtractOnStaticLoad(false); JNIWrapper.Helper.setExtractOnStaticLoad(false); @@ -55,6 +57,7 @@ public static boolean loadWpiLibraries() { "wpinetjni", "wpiHaljni", "cscorejni", + "datalogjni", "apriltagjni"); CombinedRuntimeLoader.loadLibraries(LibraryLoader.class, Core.NATIVE_LIBRARY_NAME); diff --git a/photon-targeting/src/main/native/cpp/photon/constrained_solvepnp/wrap/casadi_wrapper.cpp b/photon-targeting/src/main/native/cpp/photon/constrained_solvepnp/wrap/casadi_wrapper.cpp index 44b1acd30f..38f89bec21 100644 --- a/photon-targeting/src/main/native/cpp/photon/constrained_solvepnp/wrap/casadi_wrapper.cpp +++ b/photon-targeting/src/main/native/cpp/photon/constrained_solvepnp/wrap/casadi_wrapper.cpp @@ -157,8 +157,7 @@ struct ProblemState { #undef MAKE_ARGV }; -wpi::expected +wpi::expected constrained_solvepnp::do_optimization( bool heading_free, int nTags, constrained_solvepnp::CameraCalibration cameraCal, @@ -174,7 +173,7 @@ constrained_solvepnp::do_optimization( if constexpr (VERBOSE) fmt::println("Got unexpected num cols!"); // TODO find a new error code return wpi::unexpected{ - sleipnir::SolverExitCondition::kNonfiniteInitialCostOrConstraints}; + slp::ExitStatus::NONFINITE_INITIAL_COST_OR_CONSTRAINTS}; } // rescale observations to homogenous pixel coordinates @@ -204,7 +203,7 @@ constrained_solvepnp::do_optimization( auto problemOpt = createProblem(nTags, heading_free); if (!problemOpt) { return wpi::unexpected{ - sleipnir::SolverExitCondition::kNonfiniteInitialCostOrConstraints}; + slp::ExitStatus::NONFINITE_INITIAL_COST_OR_CONSTRAINTS}; } ProblemState<3> pState{robot2camera, field2points, point_observations, @@ -234,7 +233,7 @@ constrained_solvepnp::do_optimization( // Check for diverging iterates if (x.template lpNorm() > 1e20 || !x.allFinite()) { - return wpi::unexpected{sleipnir::SolverExitCondition::kDivergingIterates}; + return wpi::unexpected{slp::ExitStatus::DIVERGING_ITERATES}; } GradMat g = pState.calculateGradJ(x); @@ -255,7 +254,7 @@ constrained_solvepnp::do_optimization( auto H_ldlt = H.ldlt(); if (H_ldlt.info() != Eigen::Success) { std::cerr << "LDLT decomp failed! H=" << std::endl << H << std::endl; - return wpi::unexpected{sleipnir::SolverExitCondition::kLocallyInfeasible}; + return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE}; } // Make sure H is positive definite (all eigenvalues are > 0) @@ -279,8 +278,7 @@ constrained_solvepnp::do_optimization( if (H_ldlt.info() != Eigen::Success) { std::cerr << "LDLT decomp failed! H=" << std::endl << H << std::endl; - return wpi::unexpected{ - sleipnir::SolverExitCondition::kLocallyInfeasible}; + return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE}; } // If our eigenvalues aren't positive definite, pick a new δ for next @@ -290,8 +288,7 @@ constrained_solvepnp::do_optimization( // If the Hessian perturbation is too high, report failure if (δ > 1e20) { - return wpi::unexpected{ - sleipnir::SolverExitCondition::kLocallyInfeasible}; + return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE}; } } else { // Done! @@ -302,8 +299,7 @@ constrained_solvepnp::do_optimization( } if (i_reg == MAX_REG_STEPS) { - return wpi::unexpected{ - sleipnir::SolverExitCondition::kLocallyInfeasible}; + return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE}; } } else { // std::printf("Already regularized\n"); @@ -346,8 +342,7 @@ constrained_solvepnp::do_optimization( // If our step size shrank too much, report local infesibility if (alpha < α_min_frac * γConstraint) { - return wpi::unexpected{ - sleipnir::SolverExitCondition::kLocallyInfeasible}; + return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE}; } } } diff --git a/photon-targeting/src/main/native/include/photon/constrained_solvepnp/wrap/casadi_wrapper.h b/photon-targeting/src/main/native/include/photon/constrained_solvepnp/wrap/casadi_wrapper.h index da966a87e0..c71629f730 100644 --- a/photon-targeting/src/main/native/include/photon/constrained_solvepnp/wrap/casadi_wrapper.h +++ b/photon-targeting/src/main/native/include/photon/constrained_solvepnp/wrap/casadi_wrapper.h @@ -18,7 +18,7 @@ #pragma once #include -#include +#include #include namespace constrained_solvepnp { @@ -40,7 +40,7 @@ using RobotStateMat = Eigen::Matrix; * to this. The number of columns in field2points and point_observations just be * exactly 4x nTags. */ -wpi::expected do_optimization( +wpi::expected do_optimization( bool heading_free, int nTags, CameraCalibration cameraCal, // Note that casadi is column major, apparently Eigen::Matrix robot2camera, diff --git a/photon-targeting/src/main/native/jni/ConstrainedSolvepnpJNI.cpp b/photon-targeting/src/main/native/jni/ConstrainedSolvepnpJNI.cpp index 116a552046..3bff193b53 100644 --- a/photon-targeting/src/main/native/jni/ConstrainedSolvepnpJNI.cpp +++ b/photon-targeting/src/main/native/jni/ConstrainedSolvepnpJNI.cpp @@ -84,9 +84,8 @@ Java_org_photonvision_jni_ConstrainedSolvepnpJni_do_1optimization std::cout << "observations:\n" << pointObservationsMat << std::endl; #endif - wpi::expected - result = constrained_solvepnp::do_optimization( + wpi::expected result = + constrained_solvepnp::do_optimization( headingFree, nTags, cameraCal_, robot2cameraMat, xGuessMat, field2pointsMat, pointObservationsMat, gyro_θ, gyro_error_scale_fac); diff --git a/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp b/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp index f65d089777..f0f36c3de9 100644 --- a/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp +++ b/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include "jni_utils.h" #include "org_photonvision_jni_QueuedFileLogger.h" @@ -30,7 +30,7 @@ struct QueuedFileLogger { std::mutex m_mutex; - wpi::FileLogger logger; + wpi::log::FileLogger logger; explicit QueuedFileLogger(std::string_view file) : logger{file, std::bind(&QueuedFileLogger::callback, this, diff --git a/photonlib-cpp-examples/aimandrange/build.gradle b/photonlib-cpp-examples/aimandrange/build.gradle index 0c20a5cddf..b8876177e9 100644 --- a/photonlib-cpp-examples/aimandrange/build.gradle +++ b/photonlib-cpp-examples/aimandrange/build.gradle @@ -1,24 +1,14 @@ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -repositories { - mavenLocal() - jcenter() -} - -wpi.maven.useLocal = false -wpi.maven.useDevelopment = false -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you @@ -36,14 +26,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on SystemCore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcCpp +def deployArtifact = deploy.targets.systemcore.artifacts.frcCpp // Set this to true to enable desktop support. def includeDesktopSupport = true @@ -59,15 +51,7 @@ wpi.sim.addDriverstation() model { components { frcUserProgram(NativeExecutableSpec) { - // We don't need to build for roborio -- if we do, we need to install - // a roborio toolchain every time we build in CI - // Ideally, we'd be able to set the roborio toolchain as optional, but - // I can't figure out how to set that environment variable from build.gradle - // (see https://github.com/wpilibsuite/native-utils/blob/2917c69fb5094e36d499c465f047dab81c68446c/ToolchainPlugin/src/main/java/edu/wpi/first/toolchain/ToolchainGraphBuildService.java#L71) - // for now, commented out - - // targetPlatform wpi.platforms.roborio - + targetPlatform wpi.platforms.systemcore if (includeDesktopSupport) { targetPlatform wpi.platforms.desktop } diff --git a/photonlib-cpp-examples/aimandrange/settings.gradle b/photonlib-cpp-examples/aimandrange/settings.gradle index 5f9cf4bef1..64213ce87a 100644 --- a/photonlib-cpp-examples/aimandrange/settings.gradle +++ b/photonlib-cpp-examples/aimandrange/settings.gradle @@ -3,9 +3,8 @@ import org.gradle.internal.os.OperatingSystem pluginManagement { repositories { mavenLocal() - jcenter() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -21,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-cpp-examples/aimandrange/src/main/cpp/subsystems/SwerveDrive.cpp b/photonlib-cpp-examples/aimandrange/src/main/cpp/subsystems/SwerveDrive.cpp index 92801c3e4c..a7ee3eaa1b 100644 --- a/photonlib-cpp-examples/aimandrange/src/main/cpp/subsystems/SwerveDrive.cpp +++ b/photonlib-cpp-examples/aimandrange/src/main/cpp/subsystems/SwerveDrive.cpp @@ -33,7 +33,7 @@ SwerveDrive::SwerveDrive() : poseEstimator(kinematics, GetGyroYaw(), GetModulePositions(), frc::Pose2d{}, {0.1, 0.1, 0.1}, {1.0, 1.0, 1.0}), - gyroSim(gyro), + // gyroSim(gyro), swerveDriveSim(constants::Swerve::kDriveFF, frc::DCMotor::Falcon500(1), constants::Swerve::kDriveGearRatio, constants::Swerve::kWheelDiameter / 2, @@ -83,8 +83,8 @@ void SwerveDrive::ResetPose(const frc::Pose2d& pose, bool resetSimPose) { for (int i = 0; i < swerveMods.size(); i++) { swerveMods[i].SimulationUpdate(0_m, 0_mps, 0_A, 0_rad, 0_rad_per_s, 0_A); } - gyroSim.SetAngle(-pose.Rotation().Degrees()); - gyroSim.SetRate(0_rad_per_s); + // gyroSim.SetAngle(-pose.Rotation().Degrees()); + // gyroSim.SetRate(0_rad_per_s); } poseEstimator.ResetPosition(GetGyroYaw(), GetModulePositions(), pose); @@ -191,8 +191,8 @@ void SwerveDrive::SimulationPeriodic() { swerveMods[i].SimulationUpdate(drivePos, driveRate, driveCurrents[i], steerPos, steerRate, steerCurrents[i]); } - gyroSim.SetRate(-swerveDriveSim.GetOmega()); - gyroSim.SetAngle(-swerveDriveSim.GetPose().Rotation().Degrees()); + // gyroSim.SetRate(-swerveDriveSim.GetOmega()); + // gyroSim.SetAngle(-swerveDriveSim.GetPose().Rotation().Degrees()); } frc::Pose2d SwerveDrive::GetSimPose() const { return swerveDriveSim.GetPose(); } diff --git a/photonlib-cpp-examples/aimandrange/src/main/include/subsystems/SwerveDrive.h b/photonlib-cpp-examples/aimandrange/src/main/include/subsystems/SwerveDrive.h index 98b0b2a582..81e3d47bd9 100644 --- a/photonlib-cpp-examples/aimandrange/src/main/include/subsystems/SwerveDrive.h +++ b/photonlib-cpp-examples/aimandrange/src/main/include/subsystems/SwerveDrive.h @@ -24,11 +24,9 @@ #pragma once -#include -#include +#include #include #include -#include #include "SwerveDriveSim.h" #include "SwerveModule.h" @@ -70,11 +68,12 @@ class SwerveDrive { swerveMods[2].GetModuleConstants().centerOffset, swerveMods[3].GetModuleConstants().centerOffset, }; - frc::ADXRS450_Gyro gyro{frc::SPI::Port::kOnboardCS0}; + frc::OnboardIMU gyro{MountOrientation::kFlat}; frc::SwerveDrivePoseEstimator<4> poseEstimator; frc::ChassisSpeeds targetChassisSpeeds{}; - frc::sim::ADXRS450_GyroSim gyroSim; + // TODO(Jade) onboard imu doesn't have sim yet + // frc::sim::ADXRS450_GyroSim gyroSim; SwerveDriveSim swerveDriveSim; units::ampere_t totalCurrentDraw{0}; }; diff --git a/photonlib-cpp-examples/aimattarget/build.gradle b/photonlib-cpp-examples/aimattarget/build.gradle index 0c20a5cddf..b8876177e9 100644 --- a/photonlib-cpp-examples/aimattarget/build.gradle +++ b/photonlib-cpp-examples/aimattarget/build.gradle @@ -1,24 +1,14 @@ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -repositories { - mavenLocal() - jcenter() -} - -wpi.maven.useLocal = false -wpi.maven.useDevelopment = false -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you @@ -36,14 +26,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on SystemCore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcCpp +def deployArtifact = deploy.targets.systemcore.artifacts.frcCpp // Set this to true to enable desktop support. def includeDesktopSupport = true @@ -59,15 +51,7 @@ wpi.sim.addDriverstation() model { components { frcUserProgram(NativeExecutableSpec) { - // We don't need to build for roborio -- if we do, we need to install - // a roborio toolchain every time we build in CI - // Ideally, we'd be able to set the roborio toolchain as optional, but - // I can't figure out how to set that environment variable from build.gradle - // (see https://github.com/wpilibsuite/native-utils/blob/2917c69fb5094e36d499c465f047dab81c68446c/ToolchainPlugin/src/main/java/edu/wpi/first/toolchain/ToolchainGraphBuildService.java#L71) - // for now, commented out - - // targetPlatform wpi.platforms.roborio - + targetPlatform wpi.platforms.systemcore if (includeDesktopSupport) { targetPlatform wpi.platforms.desktop } diff --git a/photonlib-cpp-examples/aimattarget/settings.gradle b/photonlib-cpp-examples/aimattarget/settings.gradle index 5f9cf4bef1..64213ce87a 100644 --- a/photonlib-cpp-examples/aimattarget/settings.gradle +++ b/photonlib-cpp-examples/aimattarget/settings.gradle @@ -3,9 +3,8 @@ import org.gradle.internal.os.OperatingSystem pluginManagement { repositories { mavenLocal() - jcenter() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -21,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.jar b/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.jar index 7454180f2a..a4b76b9530 100644 Binary files a/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.jar and b/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.jar differ diff --git a/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.properties b/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.properties index 10587529d5..34bd9ce95f 100644 --- a/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.properties +++ b/photonlib-cpp-examples/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,6 @@ distributionBase=GRADLE_USER_HOME distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-8.4-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip networkTimeout=10000 validateDistributionUrl=true zipStoreBase=GRADLE_USER_HOME diff --git a/photonlib-cpp-examples/gradlew b/photonlib-cpp-examples/gradlew index 89a57c4dfe..f5feea6d6b 100755 --- a/photonlib-cpp-examples/gradlew +++ b/photonlib-cpp-examples/gradlew @@ -1,7 +1,7 @@ #!/bin/sh # -# Copyright � 2015-2021 the original authors. +# Copyright © 2015-2021 the original authors. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -15,7 +15,53 @@ # See the License for the specific language governing permissions and # limitations under the License. # +# SPDX-License-Identifier: Apache-2.0 +# +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# ############################################################################## # Attempt to set APP_HOME @@ -36,14 +82,12 @@ do esac done -# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) -APP_HOME=$( cd "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit - -APP_NAME="Gradle" +# This is normally unused +# shellcheck disable=SC2034 APP_BASE_NAME=${0##*/} - -# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. -DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' +# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) +APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s +' "$PWD" ) || exit # Use the maximum available, or set MAX_FD != -1 to use that value. MAX_FD=maximum @@ -90,22 +134,29 @@ location of your Java installation." fi else JAVACMD=java - which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + if ! command -v java >/dev/null 2>&1 + then + die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. Please set the JAVA_HOME variable in your environment to match the location of your Java installation." + fi fi # Increase the maximum file descriptors if we can. if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then case $MAX_FD in #( max*) + # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 MAX_FD=$( ulimit -H -n ) || warn "Could not query maximum file descriptor limit" esac case $MAX_FD in #( '' | soft) :;; #( *) + # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 ulimit -n "$MAX_FD" || warn "Could not set maximum file descriptor limit to $MAX_FD" esac @@ -150,11 +201,15 @@ if "$cygwin" || "$msys" ; then done fi -# Collect all arguments for the java command; -# * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of -# shell script including quotes and variable substitutions, so put them in -# double quotes to make sure that they get re-expanded; and -# * put everything else in single quotes, so that it's not re-expanded. + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Collect all arguments for the java command: +# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, +# and any embedded shellness will be escaped. +# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be +# treated as '${Hostname}' itself on the command line. set -- \ "-Dorg.gradle.appname=$APP_BASE_NAME" \ @@ -162,6 +217,12 @@ set -- \ org.gradle.wrapper.GradleWrapperMain \ "$@" +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + # Use "xargs" to parse quoted args. # # With -n1 it outputs one arg per line, with the quotes and backslashes removed. diff --git a/photonlib-cpp-examples/gradlew.bat b/photonlib-cpp-examples/gradlew.bat index 107acd32c4..9d21a21834 100644 --- a/photonlib-cpp-examples/gradlew.bat +++ b/photonlib-cpp-examples/gradlew.bat @@ -13,8 +13,10 @@ @rem See the License for the specific language governing permissions and @rem limitations under the License. @rem +@rem SPDX-License-Identifier: Apache-2.0 +@rem -@if "%DEBUG%" == "" @echo off +@if "%DEBUG%"=="" @echo off @rem ########################################################################## @rem @rem Gradle startup script for Windows @@ -25,7 +27,8 @@ if "%OS%"=="Windows_NT" setlocal set DIRNAME=%~dp0 -if "%DIRNAME%" == "" set DIRNAME=. +if "%DIRNAME%"=="" set DIRNAME=. +@rem This is normally unused set APP_BASE_NAME=%~n0 set APP_HOME=%DIRNAME% @@ -40,13 +43,13 @@ if defined JAVA_HOME goto findJavaFromJavaHome set JAVA_EXE=java.exe %JAVA_EXE% -version >NUL 2>&1 -if "%ERRORLEVEL%" == "0" goto execute +if %ERRORLEVEL% equ 0 goto execute -echo. -echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail @@ -56,11 +59,11 @@ set JAVA_EXE=%JAVA_HOME%/bin/java.exe if exist "%JAVA_EXE%" goto execute -echo. -echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail @@ -75,13 +78,15 @@ set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar :end @rem End local scope for the variables with windows NT shell -if "%ERRORLEVEL%"=="0" goto mainEnd +if %ERRORLEVEL% equ 0 goto mainEnd :fail rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of rem the _cmd.exe /c_ return code! -if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 -exit /b 1 +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% :mainEnd if "%OS%"=="Windows_NT" endlocal diff --git a/photonlib-cpp-examples/poseest/build.gradle b/photonlib-cpp-examples/poseest/build.gradle index 0c20a5cddf..b8876177e9 100644 --- a/photonlib-cpp-examples/poseest/build.gradle +++ b/photonlib-cpp-examples/poseest/build.gradle @@ -1,24 +1,14 @@ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -repositories { - mavenLocal() - jcenter() -} - -wpi.maven.useLocal = false -wpi.maven.useDevelopment = false -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you @@ -36,14 +26,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on SystemCore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcCpp +def deployArtifact = deploy.targets.systemcore.artifacts.frcCpp // Set this to true to enable desktop support. def includeDesktopSupport = true @@ -59,15 +51,7 @@ wpi.sim.addDriverstation() model { components { frcUserProgram(NativeExecutableSpec) { - // We don't need to build for roborio -- if we do, we need to install - // a roborio toolchain every time we build in CI - // Ideally, we'd be able to set the roborio toolchain as optional, but - // I can't figure out how to set that environment variable from build.gradle - // (see https://github.com/wpilibsuite/native-utils/blob/2917c69fb5094e36d499c465f047dab81c68446c/ToolchainPlugin/src/main/java/edu/wpi/first/toolchain/ToolchainGraphBuildService.java#L71) - // for now, commented out - - // targetPlatform wpi.platforms.roborio - + targetPlatform wpi.platforms.systemcore if (includeDesktopSupport) { targetPlatform wpi.platforms.desktop } diff --git a/photonlib-cpp-examples/poseest/settings.gradle b/photonlib-cpp-examples/poseest/settings.gradle index 5f9cf4bef1..64213ce87a 100644 --- a/photonlib-cpp-examples/poseest/settings.gradle +++ b/photonlib-cpp-examples/poseest/settings.gradle @@ -3,9 +3,8 @@ import org.gradle.internal.os.OperatingSystem pluginManagement { repositories { mavenLocal() - jcenter() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -21,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-java-examples/aimandrange/build.gradle b/photonlib-java-examples/aimandrange/build.gradle index 274072eb01..41b230c1f9 100644 --- a/photonlib-java-examples/aimandrange/build.gradle +++ b/photonlib-java-examples/aimandrange/build.gradle @@ -1,32 +1,25 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -sourceCompatibility = JavaVersion.VERSION_17 -targetCompatibility = JavaVersion.VERSION_17 - -def ROBOT_MAIN_CLASS = "frc.robot.Main" - -repositories { - mavenLocal(); +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 } -wpi.maven.useDevelopment = true -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - +def ROBOT_MAIN_CLASS = "frc.robot.Main" -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you // want to store a team number in this file. - team = project.frc.getTeamOrDefault(4512) + team = project.frc.getTeamOrDefault(5940) debug = project.frc.getDebugOrDefault(false) artifacts { @@ -39,14 +32,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on systemcore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcJava +def deployArtifact = deploy.targets.systemcore.artifacts.frcJava // Set to true to use debug for JNI. wpi.java.debugJni = false @@ -57,14 +52,15 @@ def includeDesktopSupport = true // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() - roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) - roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + systemcoreDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.systemcore) + systemcoreDebug wpi.java.vendor.jniDebug(wpi.platforms.systemcore) - roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) - roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + systemcoreRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.systemcore) + systemcoreRelease wpi.java.vendor.jniRelease(wpi.platforms.systemcore) nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) @@ -74,7 +70,13 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - testImplementation 'junit:junit:4.13.1' + testImplementation 'org.junit.jupiter:junit-jupiter:5.12.2' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' } // Simulation configuration (e.g. environment variables). @@ -90,6 +92,7 @@ jar { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE } diff --git a/photonlib-java-examples/aimandrange/settings.gradle b/photonlib-java-examples/aimandrange/settings.gradle index c906787bf3..64213ce87a 100644 --- a/photonlib-java-examples/aimandrange/settings.gradle +++ b/photonlib-java-examples/aimandrange/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -20,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java index c1676f6ff4..8e3fc97379 100644 --- a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java +++ b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java @@ -38,9 +38,8 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.numbers.*; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.ADXRS450_Gyro; -import edu.wpi.first.wpilibj.SPI.Port; -import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim; +import edu.wpi.first.wpilibj.OnboardIMU; +import edu.wpi.first.wpilibj.OnboardIMU.MountOrientation; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.Robot; @@ -62,7 +61,7 @@ public class SwerveDrive { swerveMods[2].getModuleConstants().centerOffset, swerveMods[3].getModuleConstants().centerOffset); - private final ADXRS450_Gyro gyro = new ADXRS450_Gyro(Port.kOnboardCS0); + private final OnboardIMU gyro = new OnboardIMU(MountOrientation.kFlat); // The robot pose estimator for tracking swerve odometry and applying vision corrections. private final SwerveDrivePoseEstimator poseEstimator; @@ -70,7 +69,8 @@ public class SwerveDrive { private ChassisSpeeds targetChassisSpeeds = new ChassisSpeeds(); // ----- Simulation - private final ADXRS450_GyroSim gyroSim; + // TODO(Jade) Onboard IMU doesnt have sim yet + // private final ADXRS450_GyroSim gyroSim; private final SwerveDriveSim swerveDriveSim; private double totalCurrentDraw = 0; @@ -91,7 +91,7 @@ public SwerveDrive() { visionStdDevs); // ----- Simulation - gyroSim = new ADXRS450_GyroSim(gyro); + // gyroSim = new ADXRS450_GyroSim(gyro); swerveDriveSim = new SwerveDriveSim( kDriveFF, @@ -117,13 +117,12 @@ public void periodic() { * Basic drive control. A target field-relative ChassisSpeeds (vx, vy, omega) is converted to * specific swerve module states. * - * @param vxMeters X velocity (forwards/backwards) - * @param vyMeters Y velocity (strafe left/right) - * @param omegaRadians Angular velocity (rotation CCW+) + * @param vx X velocity (forwards/backwards) + * @param vy Y velocity (strafe left/right) + * @param omega Angular velocity (rotation CCW+) */ - public void drive(double vxMeters, double vyMeters, double omegaRadians) { - var targetChassisSpeeds = - ChassisSpeeds.fromFieldRelativeSpeeds(vxMeters, vyMeters, omegaRadians, getHeading()); + public void drive(double vx, double vy, double omega) { + var targetChassisSpeeds = new ChassisSpeeds(vx, vy, omega).toRobotRelative(getHeading()); setChassisSpeeds(targetChassisSpeeds, true, false); } @@ -189,8 +188,8 @@ public void resetPose(Pose2d pose, boolean resetSimPose) { for (int i = 0; i < swerveMods.length; i++) { swerveMods[i].simulationUpdate(0, 0, 0, 0, 0, 0); } - gyroSim.setAngle(-pose.getRotation().getDegrees()); - gyroSim.setRate(0); + // gyroSim.setAngle(-pose.getRotation().getDegrees()); + // gyroSim.setRate(0); } poseEstimator.resetPosition(getGyroYaw(), getModulePositions(), pose); @@ -267,14 +266,13 @@ public void log() { SmartDashboard.putNumber(table + "Y", pose.getY()); SmartDashboard.putNumber(table + "Heading", pose.getRotation().getDegrees()); ChassisSpeeds chassisSpeeds = getChassisSpeeds(); - SmartDashboard.putNumber(table + "VX", chassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "VY", chassisSpeeds.vyMetersPerSecond); + SmartDashboard.putNumber(table + "VX", chassisSpeeds.vx); + SmartDashboard.putNumber(table + "VY", chassisSpeeds.vy); + SmartDashboard.putNumber(table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omega)); + SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vx); + SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vy); SmartDashboard.putNumber( - table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omegaRadiansPerSecond)); - SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vyMetersPerSecond); - SmartDashboard.putNumber( - table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omegaRadiansPerSecond)); + table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omega)); for (SwerveModule module : swerveMods) { module.log(); @@ -314,8 +312,8 @@ public void simulationPeriodic() { drivePos, driveRate, driveCurrents[i], steerPos, steerRate, steerCurrents[i]); } - gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); - gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); + // gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); + // gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); } /** diff --git a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java index ccef2bba6c..07bff21152 100644 --- a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java +++ b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java @@ -341,7 +341,7 @@ public void reset( driveStates.set(i, moduleDriveStates.get(i).copy()); steerStates.set(i, moduleSteerStates.get(i).copy()); } - omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omegaRadiansPerSecond; + omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omega; } /** @@ -444,12 +444,12 @@ public double getOmegaRadsPerSec() { */ protected static double getCurrentDraw( DCMotor motor, double radiansPerSec, double inputVolts, double battVolts) { - double effVolts = inputVolts - radiansPerSec / motor.KvRadPerSecPerVolt; + double effVolts = inputVolts - radiansPerSec / motor.Kv; // ignore regeneration if (inputVolts >= 0) effVolts = MathUtil.clamp(effVolts, 0, inputVolts); else effVolts = MathUtil.clamp(effVolts, inputVolts, 0); // calculate battery current - return (inputVolts / battVolts) * (effVolts / motor.rOhms); + return (inputVolts / battVolts) * (effVolts / motor.R); } /** diff --git a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java index 5d77dcce51..c393321713 100644 --- a/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java +++ b/photonlib-java-examples/aimandrange/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java @@ -88,12 +88,11 @@ public void periodic() { steerMotor.setVoltage(steerPid); // Use feedforward model to translate target drive velocities into voltages - double driveFF = kDriveFF.calculate(desiredState.speedMetersPerSecond); + double driveFF = kDriveFF.calculate(desiredState.speed); double drivePid = 0; if (!openLoop) { // Perform PID feedback control to compensate for disturbances - drivePid = - drivePidController.calculate(driveEncoder.getRate(), desiredState.speedMetersPerSecond); + drivePid = drivePidController.calculate(driveEncoder.getRate(), desiredState.speed); } driveMotor.setVoltage(driveFF + drivePid); @@ -156,11 +155,9 @@ public void log() { table + "Steer Degrees", Math.toDegrees(MathUtil.angleModulus(state.angle.getRadians()))); SmartDashboard.putNumber( table + "Steer Target Degrees", Math.toDegrees(steerPidController.getSetpoint())); + SmartDashboard.putNumber(table + "Drive Velocity Feet", Units.metersToFeet(state.speed)); SmartDashboard.putNumber( - table + "Drive Velocity Feet", Units.metersToFeet(state.speedMetersPerSecond)); - SmartDashboard.putNumber( - table + "Drive Velocity Target Feet", - Units.metersToFeet(desiredState.speedMetersPerSecond)); + table + "Drive Velocity Target Feet", Units.metersToFeet(desiredState.speed)); SmartDashboard.putNumber(table + "Drive Current", driveCurrentSim); SmartDashboard.putNumber(table + "Steer Current", steerCurrentSim); } diff --git a/photonlib-java-examples/aimattarget/build.gradle b/photonlib-java-examples/aimattarget/build.gradle index 15409f7cd2..41b230c1f9 100644 --- a/photonlib-java-examples/aimattarget/build.gradle +++ b/photonlib-java-examples/aimattarget/build.gradle @@ -1,28 +1,25 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -sourceCompatibility = JavaVersion.VERSION_17 -targetCompatibility = JavaVersion.VERSION_17 +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} def ROBOT_MAIN_CLASS = "frc.robot.Main" -wpi.maven.useDevelopment = true -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - - -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you // want to store a team number in this file. - team = project.frc.getTeamOrDefault(1736) + team = project.frc.getTeamOrDefault(5940) debug = project.frc.getDebugOrDefault(false) artifacts { @@ -35,14 +32,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on systemcore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcJava +def deployArtifact = deploy.targets.systemcore.artifacts.frcJava // Set to true to use debug for JNI. wpi.java.debugJni = false @@ -53,14 +52,15 @@ def includeDesktopSupport = true // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() - roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) - roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + systemcoreDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.systemcore) + systemcoreDebug wpi.java.vendor.jniDebug(wpi.platforms.systemcore) - roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) - roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + systemcoreRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.systemcore) + systemcoreRelease wpi.java.vendor.jniRelease(wpi.platforms.systemcore) nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) @@ -70,7 +70,13 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - testImplementation 'junit:junit:4.13.1' + testImplementation 'org.junit.jupiter:junit-jupiter:5.12.2' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' } // Simulation configuration (e.g. environment variables). @@ -86,6 +92,7 @@ jar { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE } diff --git a/photonlib-java-examples/aimattarget/settings.gradle b/photonlib-java-examples/aimattarget/settings.gradle index c906787bf3..64213ce87a 100644 --- a/photonlib-java-examples/aimattarget/settings.gradle +++ b/photonlib-java-examples/aimattarget/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -20,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java index c1676f6ff4..547d237bae 100644 --- a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java +++ b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java @@ -38,9 +38,8 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.numbers.*; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.ADXRS450_Gyro; -import edu.wpi.first.wpilibj.SPI.Port; -import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim; +import edu.wpi.first.wpilibj.OnboardIMU; +import edu.wpi.first.wpilibj.OnboardIMU.MountOrientation; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.Robot; @@ -62,7 +61,7 @@ public class SwerveDrive { swerveMods[2].getModuleConstants().centerOffset, swerveMods[3].getModuleConstants().centerOffset); - private final ADXRS450_Gyro gyro = new ADXRS450_Gyro(Port.kOnboardCS0); + private final OnboardIMU gyro = new OnboardIMU(MountOrientation.kFlat); // The robot pose estimator for tracking swerve odometry and applying vision corrections. private final SwerveDrivePoseEstimator poseEstimator; @@ -70,7 +69,8 @@ public class SwerveDrive { private ChassisSpeeds targetChassisSpeeds = new ChassisSpeeds(); // ----- Simulation - private final ADXRS450_GyroSim gyroSim; + // TODO(Jade) OnboardIMU doesn't have sim yet + // private final ADXRS450_GyroSim gyroSim; private final SwerveDriveSim swerveDriveSim; private double totalCurrentDraw = 0; @@ -91,7 +91,7 @@ public SwerveDrive() { visionStdDevs); // ----- Simulation - gyroSim = new ADXRS450_GyroSim(gyro); + // gyroSim = new ADXRS450_GyroSim(gyro); swerveDriveSim = new SwerveDriveSim( kDriveFF, @@ -117,13 +117,12 @@ public void periodic() { * Basic drive control. A target field-relative ChassisSpeeds (vx, vy, omega) is converted to * specific swerve module states. * - * @param vxMeters X velocity (forwards/backwards) - * @param vyMeters Y velocity (strafe left/right) - * @param omegaRadians Angular velocity (rotation CCW+) + * @param vx X velocity (forwards/backwards) + * @param vy Y velocity (strafe left/right) + * @param omega Angular velocity (rotation CCW+) */ - public void drive(double vxMeters, double vyMeters, double omegaRadians) { - var targetChassisSpeeds = - ChassisSpeeds.fromFieldRelativeSpeeds(vxMeters, vyMeters, omegaRadians, getHeading()); + public void drive(double vx, double vy, double omega) { + var targetChassisSpeeds = new ChassisSpeeds(vx, vy, omega).toRobotRelative(getHeading()); setChassisSpeeds(targetChassisSpeeds, true, false); } @@ -189,8 +188,8 @@ public void resetPose(Pose2d pose, boolean resetSimPose) { for (int i = 0; i < swerveMods.length; i++) { swerveMods[i].simulationUpdate(0, 0, 0, 0, 0, 0); } - gyroSim.setAngle(-pose.getRotation().getDegrees()); - gyroSim.setRate(0); + // gyroSim.setAngle(-pose.getRotation().getDegrees()); + // gyroSim.setRate(0); } poseEstimator.resetPosition(getGyroYaw(), getModulePositions(), pose); @@ -267,14 +266,13 @@ public void log() { SmartDashboard.putNumber(table + "Y", pose.getY()); SmartDashboard.putNumber(table + "Heading", pose.getRotation().getDegrees()); ChassisSpeeds chassisSpeeds = getChassisSpeeds(); - SmartDashboard.putNumber(table + "VX", chassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "VY", chassisSpeeds.vyMetersPerSecond); + SmartDashboard.putNumber(table + "VX", chassisSpeeds.vx); + SmartDashboard.putNumber(table + "VY", chassisSpeeds.vy); + SmartDashboard.putNumber(table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omega)); + SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vx); + SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vy); SmartDashboard.putNumber( - table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omegaRadiansPerSecond)); - SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vyMetersPerSecond); - SmartDashboard.putNumber( - table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omegaRadiansPerSecond)); + table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omega)); for (SwerveModule module : swerveMods) { module.log(); @@ -314,8 +312,8 @@ public void simulationPeriodic() { drivePos, driveRate, driveCurrents[i], steerPos, steerRate, steerCurrents[i]); } - gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); - gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); + // gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); + // gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); } /** diff --git a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java index ccef2bba6c..07bff21152 100644 --- a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java +++ b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java @@ -341,7 +341,7 @@ public void reset( driveStates.set(i, moduleDriveStates.get(i).copy()); steerStates.set(i, moduleSteerStates.get(i).copy()); } - omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omegaRadiansPerSecond; + omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omega; } /** @@ -444,12 +444,12 @@ public double getOmegaRadsPerSec() { */ protected static double getCurrentDraw( DCMotor motor, double radiansPerSec, double inputVolts, double battVolts) { - double effVolts = inputVolts - radiansPerSec / motor.KvRadPerSecPerVolt; + double effVolts = inputVolts - radiansPerSec / motor.Kv; // ignore regeneration if (inputVolts >= 0) effVolts = MathUtil.clamp(effVolts, 0, inputVolts); else effVolts = MathUtil.clamp(effVolts, inputVolts, 0); // calculate battery current - return (inputVolts / battVolts) * (effVolts / motor.rOhms); + return (inputVolts / battVolts) * (effVolts / motor.R); } /** diff --git a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java index 5d77dcce51..c393321713 100644 --- a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java +++ b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java @@ -88,12 +88,11 @@ public void periodic() { steerMotor.setVoltage(steerPid); // Use feedforward model to translate target drive velocities into voltages - double driveFF = kDriveFF.calculate(desiredState.speedMetersPerSecond); + double driveFF = kDriveFF.calculate(desiredState.speed); double drivePid = 0; if (!openLoop) { // Perform PID feedback control to compensate for disturbances - drivePid = - drivePidController.calculate(driveEncoder.getRate(), desiredState.speedMetersPerSecond); + drivePid = drivePidController.calculate(driveEncoder.getRate(), desiredState.speed); } driveMotor.setVoltage(driveFF + drivePid); @@ -156,11 +155,9 @@ public void log() { table + "Steer Degrees", Math.toDegrees(MathUtil.angleModulus(state.angle.getRadians()))); SmartDashboard.putNumber( table + "Steer Target Degrees", Math.toDegrees(steerPidController.getSetpoint())); + SmartDashboard.putNumber(table + "Drive Velocity Feet", Units.metersToFeet(state.speed)); SmartDashboard.putNumber( - table + "Drive Velocity Feet", Units.metersToFeet(state.speedMetersPerSecond)); - SmartDashboard.putNumber( - table + "Drive Velocity Target Feet", - Units.metersToFeet(desiredState.speedMetersPerSecond)); + table + "Drive Velocity Target Feet", Units.metersToFeet(desiredState.speed)); SmartDashboard.putNumber(table + "Drive Current", driveCurrentSim); SmartDashboard.putNumber(table + "Steer Current", steerCurrentSim); } diff --git a/photonlib-java-examples/aimattarget/src/test/java/frc/robot/JniLoadTest.java b/photonlib-java-examples/aimattarget/src/test/java/frc/robot/JniLoadTest.java index 07da7e010f..88d7feae2f 100644 --- a/photonlib-java-examples/aimattarget/src/test/java/frc/robot/JniLoadTest.java +++ b/photonlib-java-examples/aimattarget/src/test/java/frc/robot/JniLoadTest.java @@ -24,12 +24,12 @@ package frc.robot; -import static org.junit.Assert.fail; +import static org.junit.jupiter.api.Assertions.fail; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import java.util.List; -import org.junit.Test; +import org.junit.jupiter.api.Test; import org.photonvision.PhotonCamera; import org.photonvision.simulation.PhotonCameraSim; import org.photonvision.simulation.SimCameraProperties; diff --git a/photonlib-java-examples/gradle/wrapper/gradle-wrapper.jar b/photonlib-java-examples/gradle/wrapper/gradle-wrapper.jar index 7454180f2a..a4b76b9530 100644 Binary files a/photonlib-java-examples/gradle/wrapper/gradle-wrapper.jar and b/photonlib-java-examples/gradle/wrapper/gradle-wrapper.jar differ diff --git a/photonlib-java-examples/gradle/wrapper/gradle-wrapper.properties b/photonlib-java-examples/gradle/wrapper/gradle-wrapper.properties index 10587529d5..34bd9ce95f 100644 --- a/photonlib-java-examples/gradle/wrapper/gradle-wrapper.properties +++ b/photonlib-java-examples/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,6 @@ distributionBase=GRADLE_USER_HOME distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-8.4-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip networkTimeout=10000 validateDistributionUrl=true zipStoreBase=GRADLE_USER_HOME diff --git a/photonlib-java-examples/gradlew b/photonlib-java-examples/gradlew index 89a57c4dfe..f5feea6d6b 100755 --- a/photonlib-java-examples/gradlew +++ b/photonlib-java-examples/gradlew @@ -1,7 +1,7 @@ #!/bin/sh # -# Copyright � 2015-2021 the original authors. +# Copyright © 2015-2021 the original authors. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -15,7 +15,53 @@ # See the License for the specific language governing permissions and # limitations under the License. # +# SPDX-License-Identifier: Apache-2.0 +# +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# ############################################################################## # Attempt to set APP_HOME @@ -36,14 +82,12 @@ do esac done -# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) -APP_HOME=$( cd "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit - -APP_NAME="Gradle" +# This is normally unused +# shellcheck disable=SC2034 APP_BASE_NAME=${0##*/} - -# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. -DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' +# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) +APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s +' "$PWD" ) || exit # Use the maximum available, or set MAX_FD != -1 to use that value. MAX_FD=maximum @@ -90,22 +134,29 @@ location of your Java installation." fi else JAVACMD=java - which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + if ! command -v java >/dev/null 2>&1 + then + die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. Please set the JAVA_HOME variable in your environment to match the location of your Java installation." + fi fi # Increase the maximum file descriptors if we can. if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then case $MAX_FD in #( max*) + # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 MAX_FD=$( ulimit -H -n ) || warn "Could not query maximum file descriptor limit" esac case $MAX_FD in #( '' | soft) :;; #( *) + # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 ulimit -n "$MAX_FD" || warn "Could not set maximum file descriptor limit to $MAX_FD" esac @@ -150,11 +201,15 @@ if "$cygwin" || "$msys" ; then done fi -# Collect all arguments for the java command; -# * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of -# shell script including quotes and variable substitutions, so put them in -# double quotes to make sure that they get re-expanded; and -# * put everything else in single quotes, so that it's not re-expanded. + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Collect all arguments for the java command: +# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, +# and any embedded shellness will be escaped. +# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be +# treated as '${Hostname}' itself on the command line. set -- \ "-Dorg.gradle.appname=$APP_BASE_NAME" \ @@ -162,6 +217,12 @@ set -- \ org.gradle.wrapper.GradleWrapperMain \ "$@" +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + # Use "xargs" to parse quoted args. # # With -n1 it outputs one arg per line, with the quotes and backslashes removed. diff --git a/photonlib-java-examples/gradlew.bat b/photonlib-java-examples/gradlew.bat index 107acd32c4..9d21a21834 100644 --- a/photonlib-java-examples/gradlew.bat +++ b/photonlib-java-examples/gradlew.bat @@ -13,8 +13,10 @@ @rem See the License for the specific language governing permissions and @rem limitations under the License. @rem +@rem SPDX-License-Identifier: Apache-2.0 +@rem -@if "%DEBUG%" == "" @echo off +@if "%DEBUG%"=="" @echo off @rem ########################################################################## @rem @rem Gradle startup script for Windows @@ -25,7 +27,8 @@ if "%OS%"=="Windows_NT" setlocal set DIRNAME=%~dp0 -if "%DIRNAME%" == "" set DIRNAME=. +if "%DIRNAME%"=="" set DIRNAME=. +@rem This is normally unused set APP_BASE_NAME=%~n0 set APP_HOME=%DIRNAME% @@ -40,13 +43,13 @@ if defined JAVA_HOME goto findJavaFromJavaHome set JAVA_EXE=java.exe %JAVA_EXE% -version >NUL 2>&1 -if "%ERRORLEVEL%" == "0" goto execute +if %ERRORLEVEL% equ 0 goto execute -echo. -echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail @@ -56,11 +59,11 @@ set JAVA_EXE=%JAVA_HOME%/bin/java.exe if exist "%JAVA_EXE%" goto execute -echo. -echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% -echo. -echo Please set the JAVA_HOME variable in your environment to match the -echo location of your Java installation. +echo. 1>&2 +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 goto fail @@ -75,13 +78,15 @@ set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar :end @rem End local scope for the variables with windows NT shell -if "%ERRORLEVEL%"=="0" goto mainEnd +if %ERRORLEVEL% equ 0 goto mainEnd :fail rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of rem the _cmd.exe /c_ return code! -if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 -exit /b 1 +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% :mainEnd if "%OS%"=="Windows_NT" endlocal diff --git a/photonlib-java-examples/poseest/build.gradle b/photonlib-java-examples/poseest/build.gradle index b8ee5358ca..41b230c1f9 100644 --- a/photonlib-java-examples/poseest/build.gradle +++ b/photonlib-java-examples/poseest/build.gradle @@ -1,28 +1,25 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.3.2" + id "edu.wpi.first.GradleRIO2027" version "2027.0.0-alpha-2" } -sourceCompatibility = JavaVersion.VERSION_17 -targetCompatibility = JavaVersion.VERSION_17 +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} def ROBOT_MAIN_CLASS = "frc.robot.Main" -wpi.maven.useDevelopment = true -wpi.versions.wpilibVersion = "2025.3.2" -wpi.versions.wpimathVersion = "2025.3.2" - - -// Define my targets (RoboRIO) and artifacts (deployable files) +// Define my targets (SystemCore) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { targets { - roborio(getTargetTypeClass('RoboRIO')) { + systemcore(getTargetTypeClass('SystemCore')) { // Team number is loaded either from the .wpilib/wpilib_preferences.json // or from command line. If not found an exception will be thrown. // You can use getTeamOrDefault(team) instead of getTeamNumber if you // want to store a team number in this file. - team = project.frc.getTeamOrDefault(4512) + team = project.frc.getTeamOrDefault(5940) debug = project.frc.getDebugOrDefault(false) artifacts { @@ -35,14 +32,16 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree('src/main/deploy') - directory = '/home/lvuser/deploy' + directory = '/home/systemcore/deploy' + deleteOldFiles = false // Change to true to delete files on systemcore that no + // longer exist in deploy directory of this project } } } } } -def deployArtifact = deploy.targets.roborio.artifacts.frcJava +def deployArtifact = deploy.targets.systemcore.artifacts.frcJava // Set to true to use debug for JNI. wpi.java.debugJni = false @@ -53,14 +52,15 @@ def includeDesktopSupport = true // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() - roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) - roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + systemcoreDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.systemcore) + systemcoreDebug wpi.java.vendor.jniDebug(wpi.platforms.systemcore) - roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) - roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + systemcoreRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.systemcore) + systemcoreRelease wpi.java.vendor.jniRelease(wpi.platforms.systemcore) nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) @@ -70,7 +70,13 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - testImplementation 'junit:junit:4.13.1' + testImplementation 'org.junit.jupiter:junit-jupiter:5.12.2' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' } // Simulation configuration (e.g. environment variables). @@ -86,6 +92,7 @@ jar { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE } diff --git a/photonlib-java-examples/poseest/settings.gradle b/photonlib-java-examples/poseest/settings.gradle index c906787bf3..64213ce87a 100644 --- a/photonlib-java-examples/poseest/settings.gradle +++ b/photonlib-java-examples/poseest/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2025' + String frcYear = '2027_alpha1' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -20,8 +20,11 @@ pluginManagement { } def frcHomeMaven = new File(frcHome, 'maven') maven { - name 'frcHome' - url frcHomeMaven + name = 'frcHome' + url = frcHomeMaven } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/GamepieceLauncher.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/GamepieceLauncher.java index 8d76b1d788..93e0fd661c 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/GamepieceLauncher.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/GamepieceLauncher.java @@ -50,8 +50,7 @@ public void setRunning(boolean shouldRun) { } public void periodic() { - double maxRPM = - Units.radiansPerSecondToRotationsPerMinute(DCMotor.getFalcon500(1).freeSpeedRadPerSec); + double maxRPM = Units.radiansPerSecondToRotationsPerMinute(DCMotor.getFalcon500(1).freeSpeed); curMotorCmd = curDesSpd / maxRPM; curMotorCmd = MathUtil.clamp(curMotorCmd, 0.0, 1.0); motor.set(curMotorCmd); @@ -76,7 +75,7 @@ private void simulationInit() { public void simulationPeriodic() { launcherSim.setInputVoltage(curMotorCmd * RobotController.getBatteryVoltage()); launcherSim.update(0.02); - var spd = launcherSim.getAngularVelocityRPM(); + var spd = launcherSim.getAngularVelocity(); SmartDashboard.putNumber("GPLauncher Act Spd (RPM)", spd); } } diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java index c1676f6ff4..cdb04cff63 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDrive.java @@ -38,9 +38,8 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.numbers.*; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.ADXRS450_Gyro; -import edu.wpi.first.wpilibj.SPI.Port; -import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim; +import edu.wpi.first.wpilibj.OnboardIMU; +import edu.wpi.first.wpilibj.OnboardIMU.MountOrientation; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.Robot; @@ -62,7 +61,7 @@ public class SwerveDrive { swerveMods[2].getModuleConstants().centerOffset, swerveMods[3].getModuleConstants().centerOffset); - private final ADXRS450_Gyro gyro = new ADXRS450_Gyro(Port.kOnboardCS0); + private final OnboardIMU gyro = new OnboardIMU(MountOrientation.kFlat); // The robot pose estimator for tracking swerve odometry and applying vision corrections. private final SwerveDrivePoseEstimator poseEstimator; @@ -70,7 +69,8 @@ public class SwerveDrive { private ChassisSpeeds targetChassisSpeeds = new ChassisSpeeds(); // ----- Simulation - private final ADXRS450_GyroSim gyroSim; + // TODO(Jade) WPILib doesn't have onboard IMU sim yet + // private final ADXRS450_GyroSim gyroSim; private final SwerveDriveSim swerveDriveSim; private double totalCurrentDraw = 0; @@ -91,7 +91,7 @@ public SwerveDrive() { visionStdDevs); // ----- Simulation - gyroSim = new ADXRS450_GyroSim(gyro); + // gyroSim = new ADXRS450_GyroSim(gyro); swerveDriveSim = new SwerveDriveSim( kDriveFF, @@ -117,13 +117,12 @@ public void periodic() { * Basic drive control. A target field-relative ChassisSpeeds (vx, vy, omega) is converted to * specific swerve module states. * - * @param vxMeters X velocity (forwards/backwards) - * @param vyMeters Y velocity (strafe left/right) - * @param omegaRadians Angular velocity (rotation CCW+) + * @param vx X velocity (forwards/backwards) + * @param vy Y velocity (strafe left/right) + * @param omega Angular velocity (rotation CCW+) */ - public void drive(double vxMeters, double vyMeters, double omegaRadians) { - var targetChassisSpeeds = - ChassisSpeeds.fromFieldRelativeSpeeds(vxMeters, vyMeters, omegaRadians, getHeading()); + public void drive(double vx, double vy, double omega) { + var targetChassisSpeeds = new ChassisSpeeds(vx, vy, omega).toRobotRelative(getHeading()); setChassisSpeeds(targetChassisSpeeds, true, false); } @@ -189,8 +188,8 @@ public void resetPose(Pose2d pose, boolean resetSimPose) { for (int i = 0; i < swerveMods.length; i++) { swerveMods[i].simulationUpdate(0, 0, 0, 0, 0, 0); } - gyroSim.setAngle(-pose.getRotation().getDegrees()); - gyroSim.setRate(0); + // gyroSim.setAngle(-pose.getRotation().getDegrees()); + // gyroSim.setRate(0); } poseEstimator.resetPosition(getGyroYaw(), getModulePositions(), pose); @@ -267,14 +266,13 @@ public void log() { SmartDashboard.putNumber(table + "Y", pose.getY()); SmartDashboard.putNumber(table + "Heading", pose.getRotation().getDegrees()); ChassisSpeeds chassisSpeeds = getChassisSpeeds(); - SmartDashboard.putNumber(table + "VX", chassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "VY", chassisSpeeds.vyMetersPerSecond); + SmartDashboard.putNumber(table + "VX", chassisSpeeds.vx); + SmartDashboard.putNumber(table + "VY", chassisSpeeds.vy); + SmartDashboard.putNumber(table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omega)); + SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vx); + SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vy); SmartDashboard.putNumber( - table + "Omega Degrees", Math.toDegrees(chassisSpeeds.omegaRadiansPerSecond)); - SmartDashboard.putNumber(table + "Target VX", targetChassisSpeeds.vxMetersPerSecond); - SmartDashboard.putNumber(table + "Target VY", targetChassisSpeeds.vyMetersPerSecond); - SmartDashboard.putNumber( - table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omegaRadiansPerSecond)); + table + "Target Omega Degrees", Math.toDegrees(targetChassisSpeeds.omega)); for (SwerveModule module : swerveMods) { module.log(); @@ -314,8 +312,8 @@ public void simulationPeriodic() { drivePos, driveRate, driveCurrents[i], steerPos, steerRate, steerCurrents[i]); } - gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); - gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); + // gyroSim.setRate(-swerveDriveSim.getOmegaRadsPerSec()); + // gyroSim.setAngle(-swerveDriveSim.getPose().getRotation().getDegrees()); } /** diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java index ccef2bba6c..07bff21152 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveDriveSim.java @@ -341,7 +341,7 @@ public void reset( driveStates.set(i, moduleDriveStates.get(i).copy()); steerStates.set(i, moduleSteerStates.get(i).copy()); } - omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omegaRadiansPerSecond; + omegaRadsPerSec = kinematics.toChassisSpeeds(getModuleStates()).omega; } /** @@ -444,12 +444,12 @@ public double getOmegaRadsPerSec() { */ protected static double getCurrentDraw( DCMotor motor, double radiansPerSec, double inputVolts, double battVolts) { - double effVolts = inputVolts - radiansPerSec / motor.KvRadPerSecPerVolt; + double effVolts = inputVolts - radiansPerSec / motor.Kv; // ignore regeneration if (inputVolts >= 0) effVolts = MathUtil.clamp(effVolts, 0, inputVolts); else effVolts = MathUtil.clamp(effVolts, inputVolts, 0); // calculate battery current - return (inputVolts / battVolts) * (effVolts / motor.rOhms); + return (inputVolts / battVolts) * (effVolts / motor.R); } /** diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java index 5d77dcce51..c393321713 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/subsystems/drivetrain/SwerveModule.java @@ -88,12 +88,11 @@ public void periodic() { steerMotor.setVoltage(steerPid); // Use feedforward model to translate target drive velocities into voltages - double driveFF = kDriveFF.calculate(desiredState.speedMetersPerSecond); + double driveFF = kDriveFF.calculate(desiredState.speed); double drivePid = 0; if (!openLoop) { // Perform PID feedback control to compensate for disturbances - drivePid = - drivePidController.calculate(driveEncoder.getRate(), desiredState.speedMetersPerSecond); + drivePid = drivePidController.calculate(driveEncoder.getRate(), desiredState.speed); } driveMotor.setVoltage(driveFF + drivePid); @@ -156,11 +155,9 @@ public void log() { table + "Steer Degrees", Math.toDegrees(MathUtil.angleModulus(state.angle.getRadians()))); SmartDashboard.putNumber( table + "Steer Target Degrees", Math.toDegrees(steerPidController.getSetpoint())); + SmartDashboard.putNumber(table + "Drive Velocity Feet", Units.metersToFeet(state.speed)); SmartDashboard.putNumber( - table + "Drive Velocity Feet", Units.metersToFeet(state.speedMetersPerSecond)); - SmartDashboard.putNumber( - table + "Drive Velocity Target Feet", - Units.metersToFeet(desiredState.speedMetersPerSecond)); + table + "Drive Velocity Target Feet", Units.metersToFeet(desiredState.speed)); SmartDashboard.putNumber(table + "Drive Current", driveCurrentSim); SmartDashboard.putNumber(table + "Steer Current", steerCurrentSim); } diff --git a/shared/common.gradle b/shared/common.gradle index d383ac5918..85c1019345 100644 --- a/shared/common.gradle +++ b/shared/common.gradle @@ -24,6 +24,7 @@ dependencies { implementation 'org.msgpack:jackson-dataformat-msgpack:0.9.0' implementation wpilibTools.deps.wpilibJava("wpiutil") + implementation wpilibTools.deps.wpilibJava("datalog") implementation wpilibTools.deps.wpilibJava("cameraserver") implementation wpilibTools.deps.wpilibJava("cscore") implementation wpilibTools.deps.wpilibJava("wpinet") diff --git a/shared/config.gradle b/shared/config.gradle index 71cb2ca214..591309cd8a 100644 --- a/shared/config.gradle +++ b/shared/config.gradle @@ -1,8 +1,8 @@ // Configure Native-Utils WPI Plugin nativeUtils.addWpiNativeUtils() -nativeUtils.withCrossRoboRIO() nativeUtils.withCrossLinuxArm32() nativeUtils.withCrossLinuxArm64() +nativeUtils.withCrossSystemCore() // Configure WPI dependencies. nativeUtils.wpi.configureDependencies { diff --git a/shared/javacommon.gradle b/shared/javacommon.gradle index 7ccbaaa974..897cb4219e 100644 --- a/shared/javacommon.gradle +++ b/shared/javacommon.gradle @@ -127,6 +127,7 @@ dependencies { } implementation wpilibTools.deps.wpilibJava("wpiutil") + implementation wpilibTools.deps.wpilibJava("datalog") implementation wpilibTools.deps.wpilibJava("cameraserver") implementation wpilibTools.deps.wpilibJava("cscore") implementation wpilibTools.deps.wpilibJava("wpinet")