diff --git a/.github/workflows/gradle-build.yml b/.github/workflows/gradle-build.yml index a349598..0a24eec 100644 --- a/.github/workflows/gradle-build.yml +++ b/.github/workflows/gradle-build.yml @@ -18,13 +18,13 @@ jobs: runs-on: ubuntu-latest # This grabs the WPILib docker container - container: wpilib/roborio-cross-ubuntu:2023-22.04 + container: wpilib/roborio-cross-ubuntu:2024-22.04 # Steps represent a sequence of tasks that will be executed as part of the job steps: # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it - uses: gradle/gradle-build-action@v2 # enables fancy caching. - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - uses: gradle/wrapper-validation-action@v1 # this validates the jar file # Declares the repository safe and not under dubious ownership. @@ -44,13 +44,13 @@ jobs: runs-on: ubuntu-latest # This grabs the WPILib docker container - container: wpilib/roborio-cross-ubuntu:2023-22.04 + container: wpilib/roborio-cross-ubuntu:2024-22.04 # Steps represent a sequence of tasks that will be executed as part of the job steps: # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it - uses: gradle/gradle-build-action@v2 # enables fancy caching. - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - uses: gradle/wrapper-validation-action@v1 # this validates the jar file # Declares the repository safe and not under dubious ownership. diff --git a/.gitignore b/.gitignore index ef842c2..84cf896 100644 --- a/.gitignore +++ b/.gitignore @@ -63,9 +63,8 @@ hs_err_pid* # idea .idea/ -#exclude git info files. -src/main/deploy/branch.txt -src/main/deploy/commit.txt +#exclude git info file. +src/main/java/frc/robot/BuildConstants.java ### Linux ### *~ @@ -165,5 +164,21 @@ gradle-app.setting .settings/ bin/ +# IntelliJ +*.iml +*.ipr +*.iws +.idea/ +out/ + +# Fleet +.fleet + # Simulation GUI and other tools window save file *-window.json + +# Simulation data log directory +logs/ + +# Folder that has CTRE Phoenix Sim device config storage +ctre_sim/ diff --git a/.pathplanner/settings.json b/.pathplanner/settings.json index f15c9db..acd4977 100644 --- a/.pathplanner/settings.json +++ b/.pathplanner/settings.json @@ -2,6 +2,14 @@ "robotWidth": 0.75, "robotLength": 1.0, "holonomicMode": false, - "generateJSON": false, - "generateCSV": false + "pathFolders": [ + "New Folder" + ], + "autoFolders": [], + "defaultMaxVel": 3.0, + "defaultMaxAccel": 3.0, + "defaultMaxAngVel": 540.0, + "defaultMaxAngAccel": 720.0, + "maxModuleSpeed": 4.5, + "choreoProjectPath": null } \ No newline at end of file diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index 2260011..0aa5ada 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": false, "currentLanguage": "java", - "projectYear": "2023", + "projectYear": "2024", "teamNumber": 7652 } \ No newline at end of file diff --git a/WPILib-License.md b/WPILib-License.md index 3d5a824..43b62ec 100644 --- a/WPILib-License.md +++ b/WPILib-License.md @@ -1,4 +1,4 @@ -Copyright (c) 2009-2021 FIRST and other WPILib contributors +Copyright (c) 2009-2023 FIRST and other WPILib contributors All rights reserved. Redistribution and use in source and binary forms, with or without diff --git a/build.gradle b/build.gradle index 6b88226..f907561 100644 --- a/build.gradle +++ b/build.gradle @@ -1,11 +1,14 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2023.4.3" - id 'com.diffplug.spotless' version '6.12.0' + id "edu.wpi.first.GradleRIO" version "2024.1.1" + id 'com.diffplug.spotless' version '6.20.0' + id "com.peterabeles.gversion" version "1.10" } -sourceCompatibility = JavaVersion.VERSION_11 -targetCompatibility = JavaVersion.VERSION_11 +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} def ROBOT_MAIN_CLASS = "frc.robot.Main" @@ -44,7 +47,7 @@ def deployArtifact = deploy.targets.roborio.artifacts.frcJava wpi.java.debugJni = false // Set this to true to enable desktop support. -def includeDesktopSupport = true // groovylint-disable-line +def includeDesktopSupport = true // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. @@ -66,9 +69,8 @@ dependencies { nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) simulationRelease wpi.sim.enableRelease() - testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2' - testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2' + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' } test { @@ -84,7 +86,12 @@ wpi.sim.addDriverstation() // in order to make them all available at runtime. Also adding the manifest so WPILib // knows where to look for our Robot Class. jar { - from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + from { + configurations.runtimeClasspath.collect { + it.isDirectory() ? it : zipTree(it) + } + } + from sourceSets.main.allSource manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE } @@ -103,7 +110,7 @@ spotless { java { target fileTree('.') { include '**/*.java' - exclude '**/build/**', '**/build-*/**' + exclude '**/build/**', '**/build-*/**', '**/BuildConstants.java' } toggleOffOn() googleJavaFormat() @@ -142,45 +149,13 @@ spotless { } } -// Git Tasks -tasks.register("writeBranchName") { - // Define an output stream to write to instead of terminal - def stdout = new ByteArrayOutputStream() - - // Execute the git command - exec { - commandLine "git", "rev-parse", "--abbrev-ref", "HEAD" - // Write to the output stream instead of terminal - standardOutput = stdout - } - - // Parse the output into a string - def branch = stdout.toString().trim() - - // Create a new file - new File( - // Join project directory and deploy directory - projectDir.toString() + "/src/main/deploy", - // File name to write to - "branch.txt" - ).text = branch // Set the contents of the file to the variable branch -} - -tasks.register("writeCommitHash") { - def stdout = new ByteArrayOutputStream() - - exec { - commandLine "git", "rev-parse", "--short", "HEAD" - standardOutput = stdout - } - - def commitHash = stdout.toString().trim() - - new File( - projectDir.toString() + "/src/main/deploy", - "commit.txt" - ).text = commitHash +// Git Task +project.compileJava.dependsOn(createVersionFile) +gversion { + srcDir = "src/main/java/" + classPackage = "frc.robot" + className = "BuildConstants" + dateFormat = "yyyy-MM-dd HH:mm:ss z" + timeZone = "America/New_York" // Use preferred time zone + indent = " " } -// Make deploy depend on these tasks -deploy.targets.roborio.artifacts.frcStaticFileDeploy.dependsOn(writeBranchName) -deploy.targets.roborio.artifacts.frcStaticFileDeploy.dependsOn(writeCommitHash) diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar index 943f0cb..d64cd49 100644 Binary files a/gradle/wrapper/gradle-wrapper.jar and b/gradle/wrapper/gradle-wrapper.jar differ diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index 763a8bf..5e82d67 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,7 @@ distributionBase=GRADLE_USER_HOME distributionPath=permwrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-7.6-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip networkTimeout=10000 +validateDistributionUrl=true zipStoreBase=GRADLE_USER_HOME zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew index 65dcd68..1aa94a4 100755 --- a/gradlew +++ b/gradlew @@ -83,10 +83,8 @@ done # This is normally unused # shellcheck disable=SC2034 APP_BASE_NAME=${0##*/} -APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit - -# 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 "${APP_HOME:-./}" > /dev/null && pwd -P ) || exit # Use the maximum available, or set MAX_FD != -1 to use that value. MAX_FD=maximum @@ -133,10 +131,13 @@ 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. @@ -144,7 +145,7 @@ 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=SC3045 + # shellcheck disable=SC2039,SC3045 MAX_FD=$( ulimit -H -n ) || warn "Could not query maximum file descriptor limit" esac @@ -152,7 +153,7 @@ if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then '' | soft) :;; #( *) # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. - # shellcheck disable=SC3045 + # shellcheck disable=SC2039,SC3045 ulimit -n "$MAX_FD" || warn "Could not set maximum file descriptor limit to $MAX_FD" esac @@ -197,11 +198,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" \ diff --git a/settings.gradle b/settings.gradle index 48c039e..d94f73c 100644 --- a/settings.gradle +++ b/settings.gradle @@ -4,7 +4,7 @@ pluginManagement { repositories { mavenLocal() gradlePluginPortal() - String frcYear = '2023' + String frcYear = '2024' File frcHome if (OperatingSystem.current().isWindows()) { String publicFolder = System.getenv('PUBLIC') @@ -25,3 +25,6 @@ pluginManagement { } } } + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/src/main/deploy/pathplanner/DoNothing.path b/src/main/deploy/pathplanner/DoNothing.path deleted file mode 100644 index f7a23c6..0000000 --- a/src/main/deploy/pathplanner/DoNothing.path +++ /dev/null @@ -1,53 +0,0 @@ -{ - "waypoints": [ - { - "anchorPoint": { - "x": 1.9121419127289037, - "y": 3.0 - }, - "prevControl": null, - "nextControl": { - "x": 2.9121419127289037, - "y": 3.0 - }, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [ - "PlaceCube" - ], - "executionBehavior": "sequential", - "waitBehavior": "minimum", - "waitTime": 3.0 - } - }, - { - "anchorPoint": { - "x": 4.0, - "y": 3.0 - }, - "prevControl": { - "x": 3.6964541952294248, - "y": 3.0 - }, - "nextControl": null, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [ - "BalanceRobot" - ], - "executionBehavior": "parallel", - "waitBehavior": "none", - "waitTime": 0 - } - } - ], - "markers": [] -} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/EndAtCones.path b/src/main/deploy/pathplanner/EndAtCones.path deleted file mode 100644 index ed0e5d6..0000000 --- a/src/main/deploy/pathplanner/EndAtCones.path +++ /dev/null @@ -1,49 +0,0 @@ -{ - "waypoints": [ - { - "anchorPoint": { - "x": 2.0, - "y": 4.5 - }, - "prevControl": null, - "nextControl": { - "x": 3.0405716965280085, - "y": 4.5 - }, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [], - "executionBehavior": "sequential", - "waitBehavior": "minimum", - "waitTime": 3.0 - } - }, - { - "anchorPoint": { - "x": 6.0, - "y": 4.5 - }, - "prevControl": { - "x": 5.662926093511121, - "y": 4.5 - }, - "nextControl": null, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [], - "executionBehavior": "parallel", - "waitBehavior": "none", - "waitTime": 0 - } - } - ], - "markers": [] -} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/FullAuto.path b/src/main/deploy/pathplanner/FullAuto.path deleted file mode 100644 index 7470940..0000000 --- a/src/main/deploy/pathplanner/FullAuto.path +++ /dev/null @@ -1,54 +0,0 @@ -{ - "waypoints": [ - { - "anchorPoint": { - "x": 1.9121419127289037, - "y": 3.0 - }, - "prevControl": null, - "nextControl": { - "x": 2.9121419127289037, - "y": 3.0 - }, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [], - "executionBehavior": "sequential", - "waitBehavior": "minimum", - "waitTime": 3.0 - } - }, - { - "anchorPoint": { - "x": 4.0, - "y": 3.0 - }, - "prevControl": { - "x": 3.6964541952294248, - "y": 3.0 - }, - "nextControl": null, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [ - "BalanceRobot" - ], - "executionBehavior": "parallel", - "waitBehavior": "none", - "waitTime": 0 - } - } - ], - "maxVelocity": null, - "maxAcceleration": null, - "isReversed": false, - "markers": [] -} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/New Path.path b/src/main/deploy/pathplanner/New Path.path deleted file mode 100644 index 5162d58..0000000 --- a/src/main/deploy/pathplanner/New Path.path +++ /dev/null @@ -1,24 +0,0 @@ -{ - "waypoints": [ - { - "anchorPoint": { - "x": 1.0, - "y": 3.0 - }, - "prevControl": null, - "nextControl": null, - "holonomicAngle": 0, - "isReversal": false, - "velOverride": null, - "isLocked": false, - "isStopPoint": false, - "stopEvent": { - "names": [], - "executionBehavior": "parallel", - "waitBehavior": "none", - "waitTime": 0 - } - } - ], - "markers": [] -} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/navgrid.json b/src/main/deploy/pathplanner/navgrid.json new file mode 100644 index 0000000..bab0da9 --- /dev/null +++ b/src/main/deploy/pathplanner/navgrid.json @@ -0,0 +1 @@ +{"field_size":{"x":16.54,"y":8.21},"nodeSizeMeters":0.3,"grid":[[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,true,true],[true,true,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,true,true,true],[true,true,true,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,true,true,true,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true,true],[true,true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true,true],[true,true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true,true],[true,true,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,false,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true],[true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true]]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Example Path.path b/src/main/deploy/pathplanner/paths/Example Path.path new file mode 100644 index 0000000..3d929c7 --- /dev/null +++ b/src/main/deploy/pathplanner/paths/Example Path.path @@ -0,0 +1,65 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 2.0, + "y": 7.0 + }, + "prevControl": null, + "nextControl": { + "x": 3.0, + "y": 6.5 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 5.0, + "y": 5.0 + }, + "prevControl": { + "x": 4.0, + "y": 6.0 + }, + "nextControl": { + "x": 6.0, + "y": 4.0 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 7.0, + "y": 1.0 + }, + "prevControl": { + "x": 6.75, + "y": 2.5 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 0, + "rotateFast": false + }, + "reversed": false, + "folder": null, + "previewStartingState": null, + "useDefaultConstraints": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/TeleopSpeakerPath.path b/src/main/deploy/pathplanner/paths/TeleopSpeakerPath.path new file mode 100644 index 0000000..09f662d --- /dev/null +++ b/src/main/deploy/pathplanner/paths/TeleopSpeakerPath.path @@ -0,0 +1,49 @@ +{ + "version": 1.0, + "waypoints": [ + { + "anchor": { + "x": 5.0, + "y": 5.0 + }, + "prevControl": null, + "nextControl": { + "x": 6.0, + "y": 4.0 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 7.0, + "y": 1.0 + }, + "prevControl": { + "x": 6.75, + "y": 2.5 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0 + }, + "goalEndState": { + "velocity": 0, + "rotation": 0, + "rotateFast": false + }, + "reversed": false, + "folder": null, + "previewStartingState": null, + "useDefaultConstraints": false +} \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c1e442f..3047f6a 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -19,6 +19,11 @@ public static final class CANConstants { public static final int MOTORBACKRIGHTID = 12; public static final int MOTORFRONTLEFTID = 13; public static final int MOTORBACKLEFTID = 14; + /// Arm Motors + public static final int MOTORARMMAINID = 21; + public static final int MOTORARMSECONDARYID = 22; + /// Shooter Motors + public static final int MOTORSHOOTERID = 31; } public static final double MAX_SPEED = 0.8; @@ -32,10 +37,11 @@ public static final class CANConstants { // Joystick buttons public static final int AIMBUTTON = 12; + public static final int FIREBUTTON = 0; // Analog Ports /// Ultrasonic Sensors and ports. - public static final int ULTRASONIC1PORT = 0; + public static final int ULTRASONICSHOOTERPORT = 0; // Digital Ports /// Encoder Ports diff --git a/src/main/java/frc/robot/DriveConstants.java b/src/main/java/frc/robot/DriveConstants.java index e1412f1..7e2b56c 100644 --- a/src/main/java/frc/robot/DriveConstants.java +++ b/src/main/java/frc/robot/DriveConstants.java @@ -1,6 +1,6 @@ package frc.robot; -import com.pathplanner.lib.PathConstraints; +import com.pathplanner.lib.util.ReplanningConfig; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.kinematics.DifferentialDriveKinematics; import edu.wpi.first.math.util.Units; @@ -36,12 +36,6 @@ public final class DriveConstants { public static final double kTrackwidthMeters = 0.60048; public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackwidthMeters); - // MAX Acceleration & Velocity - public static final double kMaxSpeed = 1; // MetersPerSecond - public static final double kMaxAcceleration = 5; // MetersPerSecondSquared - public static final PathConstraints autoPathConstraints = - new PathConstraints(kMaxSpeed, kMaxAcceleration); - // Reasonable baseline values for a RAMSETE follower in units of meters and seconds - public static final double kRamseteB = 2; - public static final double kRamseteZeta = 0.7; + // Default path replanning config. See the API for the options + public static final ReplanningConfig autoReplanningConfig = new ReplanningConfig(); } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index a7e23ad..7179afb 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,20 +4,15 @@ package frc.robot; -import com.pathplanner.lib.server.PathPlannerServer; import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cscore.UsbCamera; import edu.wpi.first.cscore.VideoSink; // import edu.wpi.first.cscore.VideoSource.ConnectionStrategy; -import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.InstantCommand; -import java.io.IOException; -import java.nio.file.Files; -import java.nio.file.Path; /** * The VM is configured to automatically run this class, and to call the functions corresponding to @@ -44,7 +39,6 @@ public void robotInit() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); - PathPlannerServer.startServer(5811); // 5811 = port number. adjust this according to your needs camera1 = CameraServer.startAutomaticCapture(0); camera2 = CameraServer.startAutomaticCapture(1); @@ -53,22 +47,21 @@ public void robotInit() { // camera1.setConnectionStrategy(ConnectionStrategy.kKeepOpen); // camera2.setConnectionStrategy(ConnectionStrategy.kKeepOpen); - // this is to put git info in the dashboard & Logs - String deployDir = Filesystem.getDeployDirectory().getPath(); - String branchName = "unknown"; - String commitHash = "unknown"; - try { - branchName = Files.readString(Path.of(deployDir, "branch.txt")); - commitHash = Files.readString(Path.of(deployDir, "commit.txt")); - - } catch (IOException e) { - e.printStackTrace(); - System.out.println("Parsing Git metadata Files Failed"); - } + // this is to put git info in the dashboard & Logs, uses new 2024 BuildConstants.java + String branchName = BuildConstants.GIT_BRANCH; + String commitHash = BuildConstants.GIT_SHA; + String commitTime = BuildConstants.GIT_DATE; + String buildTime = BuildConstants.BUILD_DATE; + System.out.println("Branch: " + branchName); System.out.println("Commit: " + commitHash); + System.out.println("Commit Time: " + commitTime); + System.out.println("Build Time: " + buildTime); + SmartDashboard.putString("Branch", branchName); SmartDashboard.putString("Commit", commitHash); + SmartDashboard.putString("CommitTime", commitTime); + SmartDashboard.putString("BuildTime", buildTime); } /** diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 63e29b8..03db73e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,12 +4,15 @@ package frc.robot; -import com.pathplanner.lib.PathPlanner; -import com.pathplanner.lib.PathPlannerTrajectory; -import com.pathplanner.lib.auto.PIDConstants; -import com.pathplanner.lib.auto.RamseteAutoBuilder; -import edu.wpi.first.math.controller.RamseteController; +import com.pathplanner.lib.auto.AutoBuilder; +import com.pathplanner.lib.auto.NamedCommands; +import com.pathplanner.lib.commands.PathPlannerAuto; +import com.pathplanner.lib.path.PathConstraints; +import com.pathplanner.lib.path.PathPlannerPath; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; @@ -18,13 +21,17 @@ import edu.wpi.first.wpilibj2.command.button.JoystickButton; import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.commands.AimCommand; +import frc.robot.commands.ArmCommand; import frc.robot.commands.BalanceCommand; import frc.robot.commands.DefaultDrive; +import frc.robot.commands.ShooterCommand; import frc.robot.commands.StraightCommand; +import frc.robot.commands.UltrasonicShooterCommand; +import frc.robot.subsystems.ArmSubsystem; +import frc.robot.subsystems.CameraSubsystem; import frc.robot.subsystems.DriveSubsystem; +import frc.robot.subsystems.ShooterSubsystem; import frc.robot.subsystems.UltrasonicSubsystem; -import java.util.HashMap; -import java.util.List; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -33,6 +40,9 @@ * subsystems, commands, and button mappings) should be declared here. */ public class RobotContainer { + // These states are used to pass data between commands. + private final ShooterState m_shooterState = new ShooterState(); + // Init joysticks private final CommandXboxController m_controller1 = new CommandXboxController(Constants.CONTROLLERUSBINDEX); @@ -42,39 +52,56 @@ public class RobotContainer { // private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem(); // Init Gyro & ultrasonic - private final UltrasonicSubsystem m_ultrasonic1 = - new UltrasonicSubsystem(Constants.ULTRASONIC1PORT); + private final UltrasonicSubsystem m_ultrasonicShooterSubsystem = + new UltrasonicSubsystem(Constants.ULTRASONICSHOOTERPORT); private final DriveSubsystem m_driveSubsystem = new DriveSubsystem(); + private final CameraSubsystem m_cameraSubsystem = new CameraSubsystem(m_driveSubsystem); + private final ArmSubsystem m_armSubsystem = new ArmSubsystem(); + private final ShooterSubsystem m_shooterSubsytem = new ShooterSubsystem(); // The robots commands are defined here.. // private final ExampleCommand m_autoCommand = new ExampleCommand(m_exampleSubsystem); - private final AimCommand m_aimCommand = new AimCommand(m_driveSubsystem); + private final AimCommand m_aimCommand = new AimCommand(m_driveSubsystem, m_cameraSubsystem); private final BalanceCommand m_balanceCommand = new BalanceCommand(m_driveSubsystem); private final DefaultDrive m_defaultDrive = new DefaultDrive(m_driveSubsystem, this::getControllerLeftY, this::getControllerRightY); private final StraightCommand m_straightCommand = new StraightCommand(m_driveSubsystem, this::getControllerLeftY, this::getControllerRightY); - // misc init + private final UltrasonicShooterCommand m_ultrasonicShooterCommand = + new UltrasonicShooterCommand(m_ultrasonicShooterSubsystem, m_shooterState); + private final ArmCommand m_armCommand = + new ArmCommand(m_armSubsystem, m_shooterState, this::GetFlightStickY); + private final ShooterCommand m_shooterCommand = new ShooterCommand(m_shooterSubsytem); + private Command m_driveToSpeaker; + // Init Buttons private Trigger m_switchCameraButton; private Trigger m_balanceButton; private Trigger m_straightButton; + private Trigger m_brakeButton; + private Trigger m_coastButton; private JoystickButton m_aimButton; + private JoystickButton m_fireButton; + private Trigger m_driveToSpeakerButton; // Init For Autonomous - private RamseteAutoBuilder autoBuilder; - private final HashMap autonomousEventMap = new HashMap(); + // private RamseteAutoBuilder autoBuilder; private SendableChooser autoDashboardChooser = new SendableChooser(); - private List pathGroup; /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { - // Configure the button bindings - configureButtonBindings(); // Initialize the autonomous command initializeAutonomous(); + // Setup On the Fly Path Planning + configureTeleopPaths(); + // Configure the button bindings + configureButtonBindings(); // set default drive command m_driveSubsystem.setDefaultCommand(m_defaultDrive); + // set default command for shooter ultrasonic sensor + m_ultrasonicShooterSubsystem.setDefaultCommand(m_ultrasonicShooterCommand); + // set default command for arm + m_armSubsystem.setDefaultCommand(m_armCommand); } /** @@ -86,17 +113,23 @@ public RobotContainer() { private void configureButtonBindings() { // Controller buttons m_switchCameraButton = m_controller1.x(); + m_brakeButton = m_controller1.a(); + m_coastButton = m_controller1.b(); m_balanceButton = m_controller1.rightBumper(); m_straightButton = m_controller1.rightTrigger(); + m_driveToSpeakerButton = m_controller1.y(); // Joystick buttons m_aimButton = new JoystickButton(m_flightStick, Constants.AIMBUTTON); + m_fireButton = new JoystickButton(m_flightStick, Constants.FIREBUTTON); // commands m_balanceButton.whileTrue(m_balanceCommand); m_straightButton.whileTrue(m_straightCommand); m_aimButton.whileTrue(m_aimCommand); + m_fireButton.whileTrue(m_shooterCommand); + m_driveToSpeakerButton.whileTrue(m_driveToSpeaker); - m_controller1.a().whileTrue(new InstantCommand(() -> m_driveSubsystem.SetBrakemode())); - m_controller1.b().whileTrue(new InstantCommand(() -> m_driveSubsystem.SetCoastmode())); + m_brakeButton.whileTrue(new InstantCommand(() -> m_driveSubsystem.SetBrakemode())); + m_coastButton.whileTrue(new InstantCommand(() -> m_driveSubsystem.SetCoastmode())); } private void initializeAutonomous() { @@ -106,35 +139,44 @@ private void initializeAutonomous() { autoDashboardChooser.addOption("Do Nothing", "DoNothing"); SmartDashboard.putData(autoDashboardChooser); - // Events + // Named Commands // ex: - // autonomousEventMap.put("A", new PathFollowingCommand(m_driveSubsystem, pathGroup.get(0))); - autonomousEventMap.put("BalanceRobot", m_balanceCommand); - - // Create the AutoBuilder. This only needs to be created once when robot code starts, not every - // time you want to create an auto command. - // Use blue side of field when designing! - autoBuilder = - new RamseteAutoBuilder( - m_driveSubsystem::getPose, // Pose2d supplier - m_driveSubsystem - ::resetPose, // Pose2d consumer, used to reset odometry at the beginning of auto - new RamseteController( - DriveConstants.kRamseteB, DriveConstants.kRamseteZeta), // RamseteController - DriveConstants.kDriveKinematics, // DifferentialDriveKinematics - DriveConstants - .FeedForward, // A feedforward value to apply to the drive subsystem's controllers - m_driveSubsystem - ::getWheelSpeeds, // A method for getting the current wheel speeds of the drive - new PIDConstants( - DriveConstants.kPDriveVel, 0, 0), // A PID controller for wheel velocity control - m_driveSubsystem - ::tankDriveVolts, // A consumer that takes left and right wheel voltages and sets - // them to the drive subsystem's controllers - autonomousEventMap, - true, // change for either team - m_driveSubsystem // Requirements of the commands (should be the drive subsystem) - ); + // NamedCommands.registerCommand("A", new PathFollowingCommand(m_driveSubsystem, + // pathGroup.get(0))); + NamedCommands.registerCommand("BalanceRobot", m_balanceCommand); + + // autoBuilder = + // new RamseteAutoBuilder( + // m_driveSubsystem::getPose, // Pose2d supplier + // m_driveSubsystem + // ::resetPose, // Pose2d consumer, used to reset odometry at the beginning of auto + // new RamseteController( + // DriveConstants.kRamseteB, DriveConstants.kRamseteZeta), // RamseteController + // DriveConstants.kDriveKinematics, // DifferentialDriveKinematics + // DriveConstants + // .FeedForward, // A feedforward value to apply to the drive subsystem's + // controllers + // m_driveSubsystem::getWheelSpeeds, // A method for getting the current wheel speeds of + // the drive + // new PIDConstants( + // DriveConstants.kPDriveVel, 0, 0), // A PID controller for wheel velocity control + // m_driveSubsystem + // ::tankDriveVolts, // A consumer that takes left and right wheel voltages and sets + // // them to the drive subsystem's controllers + // autonomousEventMap, + // true, // change for either team + // m_driveSubsystem // Requirements of the commands (should be the drive subsystem) + // ); + } + + private void configureTeleopPaths() { + // Limits for all Paths + PathConstraints constraints = + new PathConstraints(3.0, 4.0, Units.degreesToRadians(540), Units.degreesToRadians(720)); + + PathPlannerPath speakerPath = PathPlannerPath.fromPathFile("TeleopSpeakerPath"); + + m_driveToSpeaker = AutoBuilder.pathfindThenFollowPath(speakerPath, constraints); } public double getControllerRightY() { @@ -145,18 +187,20 @@ public double getControllerLeftY() { return -m_controller1.getLeftY(); } + public double GetFlightStickY() { + return m_flightStick.getY(); + } + // for autonomous public DefaultDrive getDefaultDrive() { return m_defaultDrive; } - // for autonomous - public UltrasonicSubsystem getUltrasonic1() { - return m_ultrasonic1; - } + // to swap camera type. public Trigger getCameraButton() { return m_switchCameraButton; } + // for future SmartDashboard uses. public CommandXboxController getController1() { return this.m_controller1; @@ -173,10 +217,9 @@ public Joystick getFlightStick() { * @return the command to run in autonomous */ public Command getAutonomousCommand() { - pathGroup = - PathPlanner.loadPathGroup( - autoDashboardChooser.getSelected(), DriveConstants.autoPathConstraints); - // Generate the auto command from the auto builder using the routine selected in the dashboard. - return autoBuilder.fullAuto(pathGroup); + // get the name of the auto from network tables, as the rest is preconfigured by the drive + // subsystem. + String autoName = autoDashboardChooser.getSelected(); + return new PathPlannerAuto(autoName); } } diff --git a/src/main/java/frc/robot/ShooterState.java b/src/main/java/frc/robot/ShooterState.java new file mode 100644 index 0000000..fd4358c --- /dev/null +++ b/src/main/java/frc/robot/ShooterState.java @@ -0,0 +1,25 @@ +package frc.robot; + +/* + * ShooterState.java + * Tracks the status of a ring loaded in the shooter + */ +public class ShooterState { + public boolean isLoaded = false; + public boolean isLowered = false; + + public ShooterState() {} + + public void setLoaded() { + isLoaded = true; + } + + public void setFired() { + isLoaded = false; + isLowered = false; + } + + public void setLowered() { + isLowered = true; + } +} diff --git a/src/main/java/frc/robot/commands/AimCommand.java b/src/main/java/frc/robot/commands/AimCommand.java index 1a01d94..fe6a50d 100644 --- a/src/main/java/frc/robot/commands/AimCommand.java +++ b/src/main/java/frc/robot/commands/AimCommand.java @@ -6,39 +6,30 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.CameraSubsystem; import frc.robot.subsystems.DriveSubsystem; -import org.photonvision.PhotonCamera; import org.photonvision.PhotonUtils; import org.photonvision.targeting.PhotonPipelineResult; /** The Aim command that uses the camera + gyro to control the robot. */ -public class AimCommand extends CommandBase { +public class AimCommand extends Command { private final DriveSubsystem m_driveSubsystem; - private final PhotonCamera m_camera; - private final String CAMERANAME = "OV5647"; - // Constants such as camera and target height stored. Change per robot and goal! - final double CAMERA_HEIGHT_METERS = Units.inchesToMeters(24); - final double TARGET_HEIGHT_METERS = Units.feetToMeters(0.5); + private final CameraSubsystem m_cameraSubsystem; - // Angle between horizontal and the camera. - final double CAMERA_PITCH_RADIANS = Units.degreesToRadians(0); - - // How far from the target we want to be - final double GOAL_RANGE_METERS = Units.feetToMeters(3); /** * Creates a new AimCommand. * * @param d_subsystem The drive subsystem used by this command. */ - public AimCommand(DriveSubsystem d_subsystem) { + public AimCommand(DriveSubsystem d_subsystem, CameraSubsystem c_subsystem) { m_driveSubsystem = d_subsystem; + m_cameraSubsystem = c_subsystem; // Change this to match the name of your camera - m_camera = new PhotonCamera(CAMERANAME); // Use addRequirements() here to declare subsystem dependencies. - addRequirements(d_subsystem); + addRequirements(d_subsystem, c_subsystem); } // Called when the command is initially scheduled. @@ -48,7 +39,7 @@ public void initialize() {} // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - PhotonPipelineResult CamResult = m_camera.getLatestResult(); + PhotonPipelineResult CamResult = m_cameraSubsystem.frontCameraResult; // will not work if cam is defined incorrectly, but will not tell you if (CamResult.hasTargets()) { SmartDashboard.putBoolean("CameraTargetDetected", true); @@ -56,11 +47,11 @@ public void execute() { SmartDashboard.putNumber("CameraTargetPitch", angleGoal); double distanceFromTarget = PhotonUtils.calculateDistanceToTargetMeters( - CAMERA_HEIGHT_METERS, - TARGET_HEIGHT_METERS, - CAMERA_PITCH_RADIANS, + m_cameraSubsystem.frontCameraHeightMeters, + m_cameraSubsystem.frontCameraTargetHeightMeters, + m_cameraSubsystem.frontCameraTargetPitchRadians, Units.degreesToRadians(CamResult.getBestTarget().getPitch())) - - GOAL_RANGE_METERS; + - m_cameraSubsystem.frontCameraGoalRangeMeters; // turn and move towards target. m_driveSubsystem.driveAndTurn(m_driveSubsystem.getYaw(), angleGoal, distanceFromTarget); // we reset the angle everytime as the target could change / move. diff --git a/src/main/java/frc/robot/commands/ArmCommand.java b/src/main/java/frc/robot/commands/ArmCommand.java new file mode 100644 index 0000000..e40e835 --- /dev/null +++ b/src/main/java/frc/robot/commands/ArmCommand.java @@ -0,0 +1,59 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.ShooterState; +import frc.robot.subsystems.ArmSubsystem; +import java.util.function.DoubleSupplier; + +/** An example command that uses an example subsystem. */ +public class ArmCommand extends Command { + @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) + private final ArmSubsystem m_ArmSubsystem; + + private final ShooterState m_shooterState; + private final DoubleSupplier m_yAxis; + private final double kMaxRotationsPerInput = 1000; + + /** + * Creates a new ExampleCommand. + * + * @param subsystem The subsystem used by this command. + */ + public ArmCommand(ArmSubsystem a_subsystem, ShooterState shooterState, DoubleSupplier yAxis) { + m_ArmSubsystem = a_subsystem; + m_shooterState = shooterState; + m_yAxis = yAxis; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(m_ArmSubsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + if (m_yAxis.getAsDouble() != 0.0) { + m_ArmSubsystem.MoveArmRelative(m_yAxis.getAsDouble() * kMaxRotationsPerInput); + + } else if (m_shooterState.isLoaded & !m_shooterState.isLowered) { + m_ArmSubsystem.lowerArm(); + m_shooterState.setLowered(); + } + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/commands/BalanceCommand.java b/src/main/java/frc/robot/commands/BalanceCommand.java index 6354cd7..817bec1 100644 --- a/src/main/java/frc/robot/commands/BalanceCommand.java +++ b/src/main/java/frc/robot/commands/BalanceCommand.java @@ -4,11 +4,11 @@ package frc.robot.commands; -import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.DriveSubsystem; /** A Balancing command that uses the gyro subsystem. */ -public class BalanceCommand extends CommandBase { +public class BalanceCommand extends Command { private final DriveSubsystem m_driveSubsystem; /** diff --git a/src/main/java/frc/robot/commands/DefaultDrive.java b/src/main/java/frc/robot/commands/DefaultDrive.java index 6787b13..7b075f8 100644 --- a/src/main/java/frc/robot/commands/DefaultDrive.java +++ b/src/main/java/frc/robot/commands/DefaultDrive.java @@ -2,13 +2,13 @@ package frc.robot.commands; -import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.Command; import frc.robot.Constants; import frc.robot.subsystems.DriveSubsystem; import java.util.function.DoubleSupplier; /** The default drive command that uses the drive subsystem. */ -public class DefaultDrive extends CommandBase { +public class DefaultDrive extends Command { private final DriveSubsystem m_driveSubsystem; private final DoubleSupplier m_left_y; // this gives us the left y axis for current controller private final DoubleSupplier m_right_y; // this gives us the right y axis for current controller diff --git a/src/main/java/frc/robot/commands/ExampleCommand.java b/src/main/java/frc/robot/commands/ExampleCommand.java index 5150ec7..318de13 100644 --- a/src/main/java/frc/robot/commands/ExampleCommand.java +++ b/src/main/java/frc/robot/commands/ExampleCommand.java @@ -4,11 +4,11 @@ package frc.robot.commands; -import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.ExampleSubsystem; /** An example command that uses an example subsystem. */ -public class ExampleCommand extends CommandBase { +public class ExampleCommand extends Command { @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) private final ExampleSubsystem m_subsystem; diff --git a/src/main/java/frc/robot/commands/ShooterCommand.java b/src/main/java/frc/robot/commands/ShooterCommand.java new file mode 100644 index 0000000..1366a38 --- /dev/null +++ b/src/main/java/frc/robot/commands/ShooterCommand.java @@ -0,0 +1,46 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.ShooterSubsystem; + +/** A Shooter Command that uses an example subsystem. */ +public class ShooterCommand extends Command { + @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) + private final ShooterSubsystem m_shooterSubsystem; + + /** + * Creates a new ShooterCommand. + * + * @param subsystem The subsystem used by this command. + */ + public ShooterCommand(ShooterSubsystem s_subsystem) { + m_shooterSubsystem = s_subsystem; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(s_subsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + // TODO: Implement ShooterCommand + System.out.println("ShooterCommand Activated"); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/commands/StraightCommand.java b/src/main/java/frc/robot/commands/StraightCommand.java index 32fc813..39b0cdb 100644 --- a/src/main/java/frc/robot/commands/StraightCommand.java +++ b/src/main/java/frc/robot/commands/StraightCommand.java @@ -4,15 +4,16 @@ package frc.robot.commands; -import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.DriveSubsystem; import java.util.function.DoubleSupplier; /** An example command that uses an example subsystem. */ -public class StraightCommand extends CommandBase { +public class StraightCommand extends Command { private final DriveSubsystem m_driveSubsystem; private final DoubleSupplier m_left_y; // this gives us the left y axis for current controller private final DoubleSupplier m_right_y; // this gives us the right y axis for current controller + /** * Creates a new StraightCommand. * diff --git a/src/main/java/frc/robot/commands/UltrasonicShooterCommand.java b/src/main/java/frc/robot/commands/UltrasonicShooterCommand.java new file mode 100644 index 0000000..793bab6 --- /dev/null +++ b/src/main/java/frc/robot/commands/UltrasonicShooterCommand.java @@ -0,0 +1,54 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.ShooterState; +import frc.robot.subsystems.UltrasonicSubsystem; + +/** An example command that uses an example subsystem. */ +public class UltrasonicShooterCommand extends Command { + @SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"}) + private final UltrasonicSubsystem m_ultrasonicSubsystem; + + private final ShooterState m_shooterState; + + /** + * Creates a new ExampleCommand. + * + * @param subsystem The subsystem used by this command. + */ + public UltrasonicShooterCommand(UltrasonicSubsystem u_subsystem, ShooterState shooterState) { + m_ultrasonicSubsystem = u_subsystem; + m_shooterState = shooterState; + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(m_ultrasonicSubsystem); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + double distance = m_ultrasonicSubsystem.DistanceCM(); + if (distance <= 30) { + m_shooterState.setLoaded(); + } else { + m_shooterState.setFired(); + } + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.java b/src/main/java/frc/robot/subsystems/ArmSubsystem.java new file mode 100644 index 0000000..145d361 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.java @@ -0,0 +1,100 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems; + +import com.revrobotics.CANSparkBase; +import com.revrobotics.CANSparkMax; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.SparkPIDController; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.CANConstants; + +public class ArmSubsystem extends SubsystemBase { + private final CANSparkMax m_armMotorMain, m_armMotorSecondary; + private final SparkPIDController m_armMainPIDController; + private RelativeEncoder m_MainEncoder; + private final double kP, kI, kD, kIz, kFF, kMaxOutput, kMinOutput, kLoweredArmPosition; + + /** Creates a new ArmSubsystem. */ + public ArmSubsystem() { + // create the arm motors + m_armMotorMain = new CANSparkMax(CANConstants.MOTORARMMAINID, CANSparkMax.MotorType.kBrushless); + m_armMotorSecondary = + new CANSparkMax(CANConstants.MOTORARMMAINID, CANSparkMax.MotorType.kBrushless); + + // set the idle mode to brake + m_armMotorMain.setIdleMode(CANSparkMax.IdleMode.kBrake); + m_armMotorSecondary.setIdleMode(CANSparkMax.IdleMode.kBrake); + + // set the secondary motor to follow the main motor + m_armMotorSecondary.follow(m_armMotorMain); + + // connect to built in PID controller + m_armMainPIDController = m_armMotorMain.getPIDController(); + // allow us to read the encoder + m_MainEncoder = m_armMotorMain.getEncoder(); + // PID coefficients + kP = 0.1; + kI = 1e-4; + kD = 1; + kIz = 0; + kFF = 0; + kMaxOutput = 1; + kMinOutput = -1; + kLoweredArmPosition = 0; + + // set PID coefficients + m_armMainPIDController.setP(kP); + m_armMainPIDController.setI(kI); + m_armMainPIDController.setD(kD); + m_armMainPIDController.setIZone(kIz); + m_armMainPIDController.setFF(kFF); + m_armMainPIDController.setOutputRange(kMinOutput, kMaxOutput); + } + + /* + * Move arm relative to current position + */ + public void MoveArmRelative(double rotations) { + rotations = rotations + m_MainEncoder.getPosition(); + // update the PID controller with current encoder position + MoveArmToPosition(rotations); + } + + public void lowerArm() { + // move to set lowered arm position + MoveArmToPosition(kLoweredArmPosition); + } + + /* + * Move arm to global position + */ + public void MoveArmToPosition(double rotations) { + // update the PID controller with current encoder position + m_armMainPIDController.setReference(rotations, CANSparkBase.ControlType.kPosition); + } + + /* + * attempt to hold arm at current location + */ + public void stop() { + // update the PID controller with current encoder position + MoveArmToPosition(m_MainEncoder.getPosition()); + } + + public void zero() { + m_MainEncoder.setPosition(0); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + } + + @Override + public void simulationPeriodic() { + // This method will be called once per scheduler run during simulation + } +} diff --git a/src/main/java/frc/robot/subsystems/CameraSubsystem.java b/src/main/java/frc/robot/subsystems/CameraSubsystem.java new file mode 100644 index 0000000..f518a12 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/CameraSubsystem.java @@ -0,0 +1,91 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems; + +import edu.wpi.first.apriltag.AprilTagFieldLayout; +import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import java.util.Optional; +import org.photonvision.EstimatedRobotPose; +import org.photonvision.PhotonCamera; +import org.photonvision.PhotonPoseEstimator; +import org.photonvision.PhotonPoseEstimator.PoseStrategy; +import org.photonvision.targeting.PhotonPipelineResult; + +public class CameraSubsystem extends SubsystemBase { + private final DriveSubsystem m_driveSubsystem; + public final AprilTagFieldLayout aprilTagFieldLayout; + private final String frontCameraName = "OV5647"; + private final PhotonCamera frontCamera; + public PhotonPipelineResult frontCameraResult; + // Physical location of camera relative to center + private final double CameraLocationXMeters = 0.5; + private final double CameraLocationYMeters = 0.0; + private final double CameraLocationZMeters = 0.5; + // angle of camera / orientation + + // Cam mounted facing forward, half a meter forward of center, half a meter up from center. + private final double CameraRollRadians = Units.degreesToRadians(0.5); + private final double CameraPitchRadians = Units.degreesToRadians(0.0); + private final double CameraYawRadians = Units.degreesToRadians(0.5); + + private final Transform3d frontCameraLocation = + new Transform3d( + new Translation3d(CameraLocationXMeters, CameraLocationYMeters, CameraLocationZMeters), + new Rotation3d(CameraRollRadians, CameraPitchRadians, CameraYawRadians)); + + private final PhotonPoseEstimator frontCameraPoseEstimator; + // Constants such as camera and target height stored. Change per robot and goal! + public final double frontCameraHeightMeters = Units.inchesToMeters(24); + + // Target Configruation for the front camera + public final double frontCameraTargetHeightMeters = Units.feetToMeters(0.5); + // Angle between horizontal and the camera. + public final double frontCameraTargetPitchRadians = Units.degreesToRadians(0); + // How far from the target we want to be + public final double frontCameraGoalRangeMeters = Units.feetToMeters(3); + + /** Creates a new CameraSubsystem. */ + public CameraSubsystem(DriveSubsystem d_subsystem) { + m_driveSubsystem = d_subsystem; + aprilTagFieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField(); + frontCamera = new PhotonCamera(frontCameraName); + frontCameraPoseEstimator = + new PhotonPoseEstimator( + aprilTagFieldLayout, + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, + frontCamera, + frontCameraLocation); + } + + public Optional getEstimatedGlobalPose() { + return frontCameraPoseEstimator.update(); + } + + @Override + public void periodic() { + Optional pose = getEstimatedGlobalPose(); + if (pose.isPresent()) { + SmartDashboard.putBoolean("CameraConnnected", true); + m_driveSubsystem.updateVisionPose( + pose.get().estimatedPose.toPose2d(), pose.get().timestampSeconds); + } else { + SmartDashboard.putBoolean("CameraConnnected", false); + } + frontCameraResult = frontCamera.getLatestResult(); + // This method will be called once per scheduler run + SmartDashboard.putNumber("Front Camera Latency", frontCameraResult.getLatencyMillis() / 1000.0); + } + + @Override + public void simulationPeriodic() { + // This method will be called once per scheduler run during simulation + } +} diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java index 5d9d4f2..e757ad9 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -6,17 +6,20 @@ // import motor & frc dependencies import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; import com.kauailabs.navx.frc.AHRS; +import com.pathplanner.lib.auto.AutoBuilder; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.kinematics.DifferentialDriveOdometry; +import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.SPI; import edu.wpi.first.wpilibj.drive.DifferentialDrive; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; +import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; @@ -29,13 +32,10 @@ public class DriveSubsystem extends SubsystemBase { private final AHRS m_Gyro; // motors - private final WPI_VictorSPX m_backLeft; - private final WPI_VictorSPX m_frontLeft; - private final WPI_VictorSPX m_backRight; - private final WPI_VictorSPX m_frontRight; - // Motor Controllers - private final MotorControllerGroup m_motorsLeft; - private final MotorControllerGroup m_motorsRight; + private final WPI_VictorSPX m_backLeft; // Main / Master Motor for Left + private final WPI_VictorSPX m_frontLeft; // Slave Motor for Left (Follow Master) + private final WPI_VictorSPX m_backRight; // Main / Master Motor for Right + private final WPI_VictorSPX m_frontRight; // Slave Motor for Right (Follow Master) // Main drive function private final DifferentialDrive m_ddrive; @@ -44,7 +44,7 @@ public class DriveSubsystem extends SubsystemBase { private final Encoder m_encoderRight; // Odometry class for tracking robot pose (position on field) - private final DifferentialDriveOdometry m_driveOdometry; + private final DifferentialDrivePoseEstimator m_driveOdometry; // Angle PID / RotateToAngle static final double turn_P = 0.1; @@ -103,6 +103,9 @@ public class DriveSubsystem extends SubsystemBase { new TrapezoidProfile.Constraints( MaxBalanceRateDegPerS, MaxBalanceAccelerationDegPerSSquared)); + // track robot field location for dashboard + private Field2d field = new Field2d(); + /** Creates a new DriveSubsystem. */ public DriveSubsystem() { // Init gyro @@ -114,13 +117,14 @@ public DriveSubsystem() { m_frontRight = new WPI_VictorSPX(CANConstants.MOTORFRONTRIGHTID); m_backRight = new WPI_VictorSPX(CANConstants.MOTORBACKRIGHTID); - // init motor controller groups - m_motorsLeft = new MotorControllerGroup(m_backLeft, m_frontLeft); - m_motorsRight = new MotorControllerGroup(m_frontRight, m_backRight); - m_motorsRight.setInverted(true); // invert left side + // setup main and secondary motors + m_frontLeft.follow(m_backLeft); // set front left to follow back left + m_frontRight.follow(m_backRight); // set front right to follow back right + + m_backRight.setInverted(true); // invert right side // init drive function - m_ddrive = new DifferentialDrive(m_motorsLeft, m_motorsRight); + m_ddrive = new DifferentialDrive(m_backLeft, m_backRight); // init Encoders m_encoderLeft = new Encoder(Constants.DRIVEENCODERLEFTA, Constants.DRIVEENCODERLEFTB); @@ -140,8 +144,12 @@ public DriveSubsystem() { // configure Odemetry m_driveOdometry = - new DifferentialDriveOdometry( - getRotation2d(), m_encoderLeft.getDistance(), m_encoderRight.getDistance()); + new DifferentialDrivePoseEstimator( + DriveConstants.kDriveKinematics, + getRotation2d(), + m_encoderLeft.getDistance(), + m_encoderRight.getDistance(), + new Pose2d()); // config turn pid controller. m_turnController.enableContinuousInput(-180.0f, 180.0f); @@ -151,18 +159,29 @@ public DriveSubsystem() { // this is the target pitch/ tilt error. m_balanceController.setGoal(0); m_balanceController.setTolerance(BalanceToleranceDeg); // max error in degrees - } - /** - * Controls the left and right sides of the drive directly with voltages. - * - * @param leftVolts the commanded left output - * @param rightVolts the commanded right output - */ - public void tankDriveVolts(double leftVolts, double rightVolts) { - m_motorsLeft.setVoltage(leftVolts); - m_motorsRight.setVoltage(rightVolts); - m_ddrive.feed(); + // Setup Base AutoBuilder (Autonomous) + AutoBuilder.configureRamsete( + this::getPose, // Pose2d supplier + this::resetPose, // Pose2d consumer, used to reset odometry at the beginning of auto + this::getSpeeds, // A method for getting the chassis' current speed and direction + this::setSpeeds, // A consumer that takes the desired chassis speed and direction + DriveConstants.autoReplanningConfig, + () -> { + // Boolean supplier that controls when the path will be mirrored for the red alliance + // This will flip the path being followed to the red side of the field. + // THE ORIGIN WILL REMAIN ON THE BLUE SIDE + + var alliance = DriverStation.getAlliance(); + if (alliance.isPresent()) { + return alliance.get() == DriverStation.Alliance.Red; + } + return false; + }, + this // Reference to this subsystem to set requirements + ); + + SmartDashboard.putData("Field", field); // add field to dashboard } // default tank drive function @@ -286,13 +305,43 @@ public void driveStraight( this.tankDrive(leftStickValue, rightStickValue); } - // for odemetry (path following) + /* + * This function can return our robots DiffernentialDriveWheelSpeeds, which is the speed of each side of the robot. + */ public DifferentialDriveWheelSpeeds getWheelSpeeds() { return new DifferentialDriveWheelSpeeds(m_encoderLeft.getRate(), m_encoderRight.getRate()); } + /* + * This function can return our robots ChassisSpeeds, which is vx (m/s), vy (m/s), and omega (rad/s). + */ + public ChassisSpeeds getSpeeds() { + return DriveConstants.kDriveKinematics.toChassisSpeeds(getWheelSpeeds()); + } + + /* + * This function can set our robots ChassisSpeeds, which is vx (m/s), vy (m/s), and omega (rad/s). + * vy is always 0 as we are not strafing. + */ + public void setSpeeds(ChassisSpeeds speeds) { + setWheelVelocities(DriveConstants.kDriveKinematics.toWheelSpeeds(speeds)); + } + + /* + * This function can set our robots DifferentialDriveWheelSpeeds, which is the speed of each side of the robot. + */ + public void setWheelVelocities(DifferentialDriveWheelSpeeds speeds) { + // TODO: Implement, this makes everything more accurate and allows auto to work. + // https://docs.wpilib.org/en/stable/docs/software/advanced-controls/trajectories/ramsete.html#ramsete-in-the-command-based-framework + // we should use in controller velocity PID + } + public Pose2d getPose() { - return m_driveOdometry.getPoseMeters(); + return m_driveOdometry.getEstimatedPosition(); + } + + public void updateVisionPose(Pose2d visionRobotPose, double timestamp) { + m_driveOdometry.addVisionMeasurement(visionRobotPose, timestamp); } public void resetEncoders() { @@ -333,10 +382,6 @@ public void stop() { this.tankDrive(0, 0); } - public void calibrate() { - m_Gyro.calibrate(); - } - public Rotation2d getRotation2d() { return m_Gyro.getRotation2d(); } @@ -372,9 +417,11 @@ public void periodic() { SmartDashboard.putNumber("Average Distance Traveled", AverageDistance()); SmartDashboard.putNumber("Current Gyro Pitch", getPitch()); SmartDashboard.putNumber("Current Gyro Yaw", getYaw()); + SmartDashboard.putBoolean("Gyro Calibrating", m_Gyro.isCalibrating()); // Update the odometry in the periodic block m_driveOdometry.update( getRotation2d(), m_encoderLeft.getDistance(), m_encoderRight.getDistance()); + field.setRobotPose(getPose()); } @Override diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java new file mode 100644 index 0000000..9e4e8a4 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -0,0 +1,97 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems; + +import com.revrobotics.CANSparkBase; +import com.revrobotics.CANSparkMax; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.SparkPIDController; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.CANConstants; + +public class ShooterSubsystem extends SubsystemBase { + private final CANSparkMax m_ShooterMotorMain; + private final SparkPIDController m_ShooterMainPIDController; + private RelativeEncoder m_ShooterMainEncoder; + private final double kP, kI, kD, kIz, kFF, kMaxOutput, kMinOutput, maxRPM; + + /** Creates a new ShooterSubsystem. */ + public ShooterSubsystem() { + // create the shooter motors + m_ShooterMotorMain = + new CANSparkMax(CANConstants.MOTORSHOOTERID, CANSparkMax.MotorType.kBrushless); + // set the idle mode to coast + m_ShooterMotorMain.setIdleMode(CANSparkMax.IdleMode.kCoast); + + // connect to built in PID controller + m_ShooterMainPIDController = m_ShooterMotorMain.getPIDController(); + + // allow us to read the encoder + m_ShooterMainEncoder = m_ShooterMotorMain.getEncoder(); + // PID coefficients + kP = 6e-5; + kI = 0; + kD = 0; + kIz = 0; + kFF = 0.000015; + kMaxOutput = 1; + kMinOutput = -1; + maxRPM = 5700; + + // set PID coefficients + m_ShooterMainPIDController.setP(kP); + m_ShooterMainPIDController.setI(kI); + m_ShooterMainPIDController.setD(kD); + m_ShooterMainPIDController.setIZone(kIz); + m_ShooterMainPIDController.setFF(kFF); + m_ShooterMainPIDController.setOutputRange(kMinOutput, kMaxOutput); + } + + /* + * Spin shooter at a given RPM + */ + public void SpinShooter(double RPM) { + m_ShooterMainPIDController.setReference(RPM, CANSparkBase.ControlType.kVelocity); + } + + /* + * Stop the shooter + */ + public void StopShooter() { + SpinShooter(0); + } + + /* + * Spin Shooter at max RPM + */ + public void SpinShooterFull() { + SpinShooter(maxRPM); + } + + /* + * Check if shooter is at a given RPM + */ + public Boolean isAtRPMTolerance(double RPM) { + return (m_ShooterMainEncoder.getVelocity() > RPM - 100 + && m_ShooterMainEncoder.getVelocity() < RPM + 100); + } + + /* + * Check if shooter is at max RPM + */ + public Boolean isAtMaxRPM() { + return isAtRPMTolerance(maxRPM); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + } + + @Override + public void simulationPeriodic() { + // This method will be called once per scheduler run during simulation + } +} diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json index 29ec93a..e978a5f 100644 --- a/vendordeps/NavX.json +++ b/vendordeps/NavX.json @@ -1,17 +1,18 @@ { "fileName": "NavX.json", - "name": "KauaiLabs_navX_FRC", - "version": "2023.0.3", + "name": "NavX", + "version": "2024.1.0", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "frcYear": "2024", "mavenUrls": [ - "https://dev.studica.com/maven/release/2023/" + "https://dev.studica.com/maven/release/2024/" ], - "jsonUrl": "https://dev.studica.com/releases/2023/NavX.json", + "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json", "javaDependencies": [ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-frc-java", - "version": "2023.0.3" + "version": "2024.1.0" } ], "jniDependencies": [], @@ -19,7 +20,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-frc-cpp", - "version": "2023.0.3", + "version": "2024.1.0", "headerClassifier": "headers", "sourcesClassifier": "sources", "sharedLibrary": false, @@ -30,7 +31,7 @@ "linuxraspbian", "linuxarm32", "linuxarm64", - "linux86-64", + "linuxx86-64", "osxuniversal", "windowsx86-64" ] diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index 8e61586..3c74146 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,8 +1,9 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2023.4.4", + "version": "2024.1.2", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", + "frcYear": "2024", "mavenUrls": [ "https://3015rangerrobotics.github.io/pathplannerlib/repo" ], @@ -11,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2023.4.4" + "version": "2024.1.2" } ], "jniDependencies": [], @@ -19,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2023.4.4", + "version": "2024.1.2", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -28,7 +29,9 @@ "windowsx86-64", "linuxx86-64", "osxuniversal", - "linuxathena" + "linuxathena", + "linuxarm32", + "linuxarm64" ] } ] diff --git a/vendordeps/Phoenix5.json b/vendordeps/Phoenix5.json new file mode 100644 index 0000000..88a68dd --- /dev/null +++ b/vendordeps/Phoenix5.json @@ -0,0 +1,151 @@ +{ + "fileName": "Phoenix5.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.33.0", + "frcYear": 2024, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json", + "requires": [ + { + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", + "offlineFileName": "Phoenix6.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.33.0" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.33.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.33.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.33.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.33.0", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.33.0", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.33.0", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.33.0", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.33.0", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.33.0", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix6.json similarity index 69% rename from vendordeps/Phoenix.json rename to vendordeps/Phoenix6.json index 614dc3a..69a4079 100644 --- a/vendordeps/Phoenix.json +++ b/vendordeps/Phoenix6.json @@ -1,56 +1,32 @@ { - "fileName": "Phoenix.json", - "name": "CTRE-Phoenix (v5)", - "version": "5.31.0+23.2.2", - "frcYear": 2023, - "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "fileName": "Phoenix6.json", + "name": "CTRE-Phoenix (v6)", + "version": "24.1.0", + "frcYear": 2024, + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ "https://maven.ctr-electronics.com/release/" ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json", - "javaDependencies": [ + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", + "conflictsWith": [ { - "groupId": "com.ctre.phoenix", - "artifactId": "api-java", - "version": "5.31.0" - }, + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", + "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", + "offlineFileName": "Phoenix6And5.json" + } + ], + "javaDependencies": [ { - "groupId": "com.ctre.phoenix", + "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "5.31.0" + "version": "24.1.0" } ], "jniDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.31.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.31.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -63,7 +39,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -76,7 +52,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -89,7 +65,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonFX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -102,7 +78,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -115,7 +91,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -128,7 +104,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -141,7 +117,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -154,7 +130,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -167,7 +143,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,40 +156,10 @@ ], "cppDependencies": [ { - "groupId": "com.ctre.phoenix", + "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "5.31.0", - "libName": "CTRE_Phoenix_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-cpp", - "version": "5.31.0", - "libName": "CTRE_Phoenix", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.31.0", - "libName": "CTRE_PhoenixCCI", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -227,7 +173,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -240,40 +186,10 @@ "simMode": "hwsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.31.0", - "libName": "CTRE_Phoenix_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "api-cpp-sim", - "version": "5.31.0", - "libName": "CTRE_PhoenixSim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.31.0", - "libName": "CTRE_PhoenixCCISim", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -287,7 +203,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -302,7 +218,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -317,7 +233,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonFX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -332,7 +248,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -347,7 +263,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -362,7 +278,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -377,7 +293,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -392,7 +308,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -407,7 +323,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index f2d0b7d..0f3520e 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,24 +1,25 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2023.1.3", + "version": "2024.2.0", + "frcYear": "2024", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2023.1.3" + "version": "2024.2.0" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.2.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2023.1.3", + "version": "2024.2.0", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -54,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.2.0", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index 65dcc03..67bf389 100644 --- a/vendordeps/WPILibNewCommands.json +++ b/vendordeps/WPILibNewCommands.json @@ -3,35 +3,36 @@ "name": "WPILib-New-Commands", "version": "1.0.0", "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "frcYear": "2024", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-java", - "version": "wpilib" - } + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } ], "jniDependencies": [], "cppDependencies": [ - { - "groupId": "edu.wpi.first.wpilibNewCommands", - "artifactId": "wpilibNewCommands-cpp", - "version": "wpilib", - "libName": "wpilibNewCommands", - "headerClassifier": "headers", - "sourcesClassifier": "sources", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "linuxathena", - "linuxarm32", - "linuxarm64", - "windowsx86-64", - "windowsx86", - "linuxx86-64", - "osxuniversal" - ] - } + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxuniversal" + ] + } ] } diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index dad3105..8a0e424 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,41 +1,57 @@ { - "fileName": "photonlib.json", - "name": "photonlib", - "version": "v2023.4.2", - "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004 ", - "mavenUrls": [ - "https://maven.photonvision.org/repository/internal", - "https://maven.photonvision.org/repository/snapshots" - ], - "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/PhotonLib-json/1.0/PhotonLib-json-1.0.json", - "jniDependencies": [], - "cppDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "PhotonLib-cpp", - "version": "v2023.4.2", - "libName": "Photon", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxathena", - "linuxx86-64", - "osxuniversal" - ] - } - ], - "javaDependencies": [ - { - "groupId": "org.photonvision", - "artifactId": "PhotonLib-java", - "version": "v2023.4.2" - }, - { - "groupId": "org.photonvision", - "artifactId": "PhotonTargeting-java", - "version": "v2023.4.2" - } - ] -} \ No newline at end of file + "fileName": "photonlib.json", + "name": "photonlib", + "version": "v2024.1.2", + "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", + "frcYear": "2024", + "mavenUrls": [ + "https://maven.photonvision.org/repository/internal", + "https://maven.photonvision.org/repository/snapshots" + ], + "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/PhotonLib-json/1.0/PhotonLib-json-1.0.json", + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "photonlib-cpp", + "version": "v2024.1.2", + "libName": "photonlib", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-cpp", + "version": "v2024.1.2", + "libName": "photontargeting", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + } + ], + "javaDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "photonlib-java", + "version": "v2024.1.2" + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-java", + "version": "v2024.1.2" + } + ] +}