diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..a8d1911 --- /dev/null +++ b/.gitignore @@ -0,0 +1,172 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### Java ### +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +### Linux ### +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +### macOS ### +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +### Gradle ### +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ + +# IntelliJ +*.iml +*.ipr +*.iws +.idea/ +out/ + +# Fleet +.fleet + +# Simulation GUI and other tools window save file +*-window.json diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..c9c9713 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,21 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + + { + "type": "wpilib", + "name": "WPILib Desktop Debug", + "request": "launch", + "desktop": true, + }, + { + "type": "wpilib", + "name": "WPILib roboRIO Debug", + "request": "launch", + "desktop": false, + } + ] +} diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..4ed293b --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,29 @@ +{ + "java.configuration.updateBuildConfiguration": "automatic", + "java.server.launchMode": "Standard", + "files.exclude": { + "**/.git": true, + "**/.svn": true, + "**/.hg": true, + "**/CVS": true, + "**/.DS_Store": true, + "bin/": true, + "**/.classpath": true, + "**/.project": true, + "**/.settings": true, + "**/.factorypath": true, + "**/*~": true + }, + "java.test.config": [ + { + "name": "WPIlibUnitTests", + "workingDirectory": "${workspaceFolder}/build/jni/release", + "vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ], + "env": { + "LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" , + "DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" + } + }, + ], + "java.test.defaultConfig": "WPIlibUnitTests" +} diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 0000000..b5a7052 --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2023", + "teamNumber": 178 +} \ No newline at end of file diff --git a/TODO.md b/TODO.md new file mode 100644 index 0000000..aa8cd25 --- /dev/null +++ b/TODO.md @@ -0,0 +1 @@ +- set actual arm positions \ No newline at end of file diff --git a/WPILib-License.md b/WPILib-License.md new file mode 100644 index 0000000..3d5a824 --- /dev/null +++ b/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2021 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/build.gradle b/build.gradle new file mode 100644 index 0000000..b3109ac --- /dev/null +++ b/build.gradle @@ -0,0 +1,99 @@ +plugins { + id "java" + id "edu.wpi.first.GradleRIO" version "2023.4.3" +} + +sourceCompatibility = JavaVersion.VERSION_11 +targetCompatibility = JavaVersion.VERSION_11 + +def ROBOT_MAIN_CLASS = "frc.robot.Main" + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = true + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 5. +dependencies { + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + 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' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// 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) } } + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000..249e583 Binary files /dev/null and b/gradle/wrapper/gradle-wrapper.jar differ diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 0000000..c23a1b3 --- /dev/null +++ b/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,5 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-7.5.1-bin.zip +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew new file mode 100644 index 0000000..a69d9cb --- /dev/null +++ b/gradlew @@ -0,0 +1,240 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/master/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit + +APP_NAME="Gradle" +APP_BASE_NAME=${0##*/} + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +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. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + 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. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/gradlew.bat b/gradlew.bat new file mode 100644 index 0000000..f127cfd --- /dev/null +++ b/gradlew.bat @@ -0,0 +1,91 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem + +@if "%DEBUG%"=="" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%"=="" set DIRNAME=. +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if %ERRORLEVEL% equ 0 goto execute + +echo. +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if %ERRORLEVEL% equ 0 goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/settings.gradle b/settings.gradle new file mode 100644 index 0000000..48c039e --- /dev/null +++ b/settings.gradle @@ -0,0 +1,27 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2023' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt new file mode 100644 index 0000000..bb82515 --- /dev/null +++ b/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java new file mode 100644 index 0000000..28aea8b --- /dev/null +++ b/src/main/java/frc/robot/Constants.java @@ -0,0 +1,152 @@ +// 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; + +import edu.wpi.first.wpilibj.Preferences; + +/** + * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean + * constants. This class should not be used for any other purpose. All constants should be declared + * globally (i.e. public static). Do not put anything functional in this class. + * + *

It is advised to statically import this class (or one of its inner classes) wherever the + * constants are needed, to reduce verbosity. + */ +public final class Constants { + public static class ArmConstants { + public static final int kLowerSparkPort = 20; + public static final int kUpperSparkPort = 21; + public static final int kLowerEncoderChannel = 7; + public static final int kUpperEncoderChannel = 8; + public static final int kLowerLimitChannel = 0; + public static final int kUpperLimitChannel = 1; + + public static final double kLowerOffset = 304.632908 - 180; // opposite - 180 + public static final double kUpperOffset = 279.201265 - 90; // vertical - 90 + public static final double kLowerMaxVolts = 4; + public static final double kUpperMaxVolts = 6; + + public static final double kDefaultLowerP = 0.05; + public static final double kDefaultLowerI = 0.003; + public static final double kDefaultLowerD = 0; + public static final double kDefaultLowerS = 0; + public static final double kDefaultLowerG = 0.2; + public static final double kDefaultLowerV = 0; + public static final double kDefaultLowerA = 0; + + public static final double kDefaultUpperP = 0.06; + public static final double kDefaultUpperI = 0.004; + public static final double kDefaultUpperD = 0; + public static final double kDefaultUpperS = 0; + public static final double kDefaultUpperG = 0.2; + public static final double kDefaultUpperV = 0; + public static final double kDefaultUpperA = 0; + + public static void initArmPreferences() { + Preferences.initDouble("kArmLowerP", ArmConstants.kDefaultLowerP); + Preferences.initDouble("kArmLowerI", ArmConstants.kDefaultLowerI); + Preferences.initDouble("kArmLowerD", ArmConstants.kDefaultLowerD); + Preferences.initDouble("kArmLowerS", ArmConstants.kDefaultLowerS); + Preferences.initDouble("kArmLowerG", ArmConstants.kDefaultLowerG); + Preferences.initDouble("kArmLowerV", ArmConstants.kDefaultLowerV); + Preferences.initDouble("kArmLowerA", ArmConstants.kDefaultLowerA); + + Preferences.initDouble("kArmUpperP", ArmConstants.kDefaultUpperP); + Preferences.initDouble("kArmUpperI", ArmConstants.kDefaultUpperI); + Preferences.initDouble("kArmUpperD", ArmConstants.kDefaultUpperD); + Preferences.initDouble("kArmUpperS", ArmConstants.kDefaultUpperS); + Preferences.initDouble("kArmUpperG", ArmConstants.kDefaultUpperG); + Preferences.initDouble("kArmUpperV", ArmConstants.kDefaultUpperV); + Preferences.initDouble("kArmUpperA", ArmConstants.kDefaultUpperA); + + System.out.println("Arm robot preferences initialized."); + } + + public static void resetArmPreferences() { + Preferences.setDouble("kArmLowerP", ArmConstants.kDefaultLowerP); + Preferences.setDouble("kArmLowerI", ArmConstants.kDefaultLowerI); + Preferences.setDouble("kArmLowerD", ArmConstants.kDefaultLowerD); + Preferences.setDouble("kArmLowerS", ArmConstants.kDefaultLowerS); + Preferences.setDouble("kArmLowerG", ArmConstants.kDefaultLowerG); + Preferences.setDouble("kArmLowerV", ArmConstants.kDefaultLowerV); + Preferences.setDouble("kArmLowerA", ArmConstants.kDefaultLowerA); + + Preferences.setDouble("kArmUpperP", ArmConstants.kDefaultUpperP); + Preferences.setDouble("kArmUpperI", ArmConstants.kDefaultUpperI); + Preferences.setDouble("kArmUpperD", ArmConstants.kDefaultUpperD); + Preferences.setDouble("kArmUpperS", ArmConstants.kDefaultUpperS); + Preferences.setDouble("kArmUpperG", ArmConstants.kDefaultUpperG); + Preferences.setDouble("kArmUpperV", ArmConstants.kDefaultUpperV); + Preferences.setDouble("kArmUpperA", ArmConstants.kDefaultUpperA); + + System.out.println("Arm robot preferences reset."); + } + + public static double getKLowerP() { + return Preferences.getDouble("kArmLowerP", kDefaultLowerP); + } + + public static double getKLowerI() { + return Preferences.getDouble("kArmLowerI", kDefaultLowerI); + } + + public static double getKLowerD() { + return Preferences.getDouble("kArmLowerD", kDefaultLowerD); + } + + public static double getKLowerS() { + return Preferences.getDouble("kArmLowerS", kDefaultLowerS); + } + + public static double getKLowerG() { + return Preferences.getDouble("kArmLowerG", kDefaultLowerG); + } + + public static double getKLowerV() { + return Preferences.getDouble("kArmLowerV", kDefaultLowerV); + } + + public static double getKLowerA() { + return Preferences.getDouble("kArmLowerA", kDefaultLowerA); + } + + public static double getKUpperP() { + return Preferences.getDouble("kArmUpperP", kDefaultUpperP); + } + + public static double getKUpperI() { + return Preferences.getDouble("kArmUpperI", kDefaultUpperI); + } + + public static double getKUpperD() { + return Preferences.getDouble("kArmUpperD", kDefaultUpperD); + } + + public static double getKUpperS() { + return Preferences.getDouble("kArmUpperS", kDefaultUpperS); + } + + public static double getKUpperG() { + return Preferences.getDouble("kArmUpperG", kDefaultUpperG); + } + + public static double getKUpperV() { + return Preferences.getDouble("kArmUpperV", kDefaultUpperV); + } + + public static double getKUpperA() { + return Preferences.getDouble("kArmUpperA", kDefaultUpperA); + } + } + + public static class ClawConstants { + public static final int kSolenoidPort = 6; + } + + public static class OperatorConstants { + public static final int kDriverControllerPort = 0; + public static final int kAuxDriverControllerPort = 1; + } +} diff --git a/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/Main.java new file mode 100644 index 0000000..8776e5d --- /dev/null +++ b/src/main/java/frc/robot/Main.java @@ -0,0 +1,25 @@ +// 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; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java new file mode 100644 index 0000000..687a0a0 --- /dev/null +++ b/src/main/java/frc/robot/Robot.java @@ -0,0 +1,103 @@ +// 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; + +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; + +/** + * The VM is configured to automatically run this class, and to call the functions corresponding to + * each mode, as described in the TimedRobot documentation. If you change the name of this class or + * the package after creating this project, you must also update the build.gradle file in the + * project. + */ +public class Robot extends TimedRobot { + private Command m_autonomousCommand; + + private RobotContainer m_robotContainer; + + /** + * This function is run when the robot is first started up and should be used for any + * initialization code. + */ + @Override + 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(); + } + + /** + * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics + * that you want ran during disabled, autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic functions, but before LiveWindow and + * SmartDashboard integrated updating. + */ + @Override + public void robotPeriodic() { + // Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled + // commands, running already-scheduled commands, removing finished or interrupted commands, + // and running subsystem periodic() methods. This must be called from the robot's periodic + // block in order for anything in the Command-based framework to work. + CommandScheduler.getInstance().run(); + } + + /** This function is called once each time the robot enters Disabled mode. */ + @Override + public void disabledInit() {} + + @Override + public void disabledPeriodic() {} + + /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ + @Override + public void autonomousInit() { + m_autonomousCommand = m_robotContainer.getAutonomousCommand(); + + // schedule the autonomous command (example) + if (m_autonomousCommand != null) { + m_autonomousCommand.schedule(); + } + } + + /** This function is called periodically during autonomous. */ + @Override + public void autonomousPeriodic() {} + + @Override + public void teleopInit() { + // This makes sure that the autonomous stops running when + // teleop starts running. If you want the autonomous to + // continue until interrupted by another command, remove + // this line or comment it out. + if (m_autonomousCommand != null) { + m_autonomousCommand.cancel(); + } + } + + /** This function is called periodically during operator control. */ + @Override + public void teleopPeriodic() {} + + @Override + public void testInit() { + // Cancels all running commands at the start of test mode. + CommandScheduler.getInstance().cancelAll(); + } + + /** This function is called periodically during test mode. */ + @Override + public void testPeriodic() {} + + /** This function is called once when the robot is first started up. */ + @Override + public void simulationInit() {} + + /** This function is called periodically whilst in simulation. */ + @Override + public void simulationPeriodic() {} +} diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java new file mode 100644 index 0000000..a58605f --- /dev/null +++ b/src/main/java/frc/robot/RobotContainer.java @@ -0,0 +1,82 @@ +// 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; + +import frc.robot.Constants.OperatorConstants; +import frc.robot.commands.arm.ArmPosition; +import frc.robot.subsystems.Arm; +import frc.robot.subsystems.Claw; +import edu.wpi.first.wpilibj.Preferences; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; + +/** + * This class is where the bulk of the robot should be declared. Since Command-based is a + * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} + * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including + * subsystems, commands, and trigger mappings) should be declared here. + */ +public class RobotContainer { + + private final CommandXboxController m_driverController = new CommandXboxController(OperatorConstants.kDriverControllerPort); + private final CommandXboxController m_auxController = new CommandXboxController(OperatorConstants.kAuxDriverControllerPort); + + private Arm m_arm; + private Claw m_claw; + + /** The container for the robot. Contains subsystems, OI devices, and commands. */ + public RobotContainer() { + Preferences.removeAll(); + m_arm = new Arm(); + m_claw = new Claw(); + // Configure the trigger bindings + configureBindings(); + } + + /** + * Use this method to define your trigger->command mappings. Triggers can be created via the + * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary + * predicate, or via the named factories in {@link + * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link + * CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller + * PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight + * joysticks}. + */ + private void configureBindings() { + m_auxController.leftBumper().onTrue(m_claw.runToggleClaw()); + + m_auxController.leftStick().onTrue(m_arm.runLowerTest()); + m_auxController.leftStick().onFalse(m_arm.runCutMotors()); + m_auxController.rightStick().onTrue(m_arm.runUpperTest()); + m_auxController.rightStick().onFalse(m_arm.runCutMotors()); + + m_auxController.rightTrigger().onTrue(m_arm.runToSetpoint()); + m_auxController.rightTrigger().onFalse(m_arm.runGetOffSetpoint()); + + m_auxController.b().onTrue(m_arm.runSetArmPosition(ArmPosition.HOME)); + m_auxController.y().onTrue(m_arm.runSetArmPosition(ArmPosition.SUBSTATION)); + // m_auxController.a().onTrue(m_arm.runSetArmPosition(ArmPosition.LOW)); + // m_auxController.x().onTrue(m_arm.runSetArmPosition(ArmPosition.HIGH)); + m_auxController.rightBumper().onTrue(m_arm.runSetArmPosition(ArmPosition.BACK)); + + m_auxController.povUpLeft().whileTrue(m_arm.runBumpLower(-0.1)); + m_auxController.povDownLeft().whileTrue(m_arm.runBumpLower(0.1)); + + m_auxController.povUpRight().whileTrue(m_arm.runBumpUpper(-0.1)); + m_auxController.povDownRight().whileTrue(m_arm.runBumpUpper(0.1)); + } + + /** + * Use this to pass the autonomous command to the main {@link Robot} class. + * + * @return the command to run in autonomous + */ + public Command getAutonomousCommand() { + // An example command will be run in autonomous + return Commands.run(() -> {}); + } +} diff --git a/src/main/java/frc/robot/commands/Autos.java b/src/main/java/frc/robot/commands/Autos.java new file mode 100644 index 0000000..63f6629 --- /dev/null +++ b/src/main/java/frc/robot/commands/Autos.java @@ -0,0 +1,19 @@ +// 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.CommandBase; +import edu.wpi.first.wpilibj2.command.Commands; + +public final class Autos { + /** Example static factory for an autonomous command. */ + // public static CommandBase exampleAuto(ExampleSubsystem subsystem) { + // return Commands.sequence(subsystem.exampleMethodCommand(), new ExampleCommand(subsystem)); + // } + + // private Autos() { + // throw new UnsupportedOperationException("This is a utility class!"); + // } +} diff --git a/src/main/java/frc/robot/commands/arm/ArmFF.java b/src/main/java/frc/robot/commands/arm/ArmFF.java new file mode 100644 index 0000000..bd0a80c --- /dev/null +++ b/src/main/java/frc/robot/commands/arm/ArmFF.java @@ -0,0 +1,183 @@ +// 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. + +// Edited by Team 178 for adjustable constants + +package frc.robot.commands.arm; + +/** + * A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting + * against the force of gravity on a beam suspended at an angle). + */ +public class ArmFF { + private double ks; + private double kg; + private double kv; + private double ka; + + /** + * Creates a new ArmFF with the specified gains. Units of the gain values will dictate + * units of the computed feedforward. + * + * @param ks The static gain. + * @param kg The gravity gain. + * @param kv The velocity gain. + * @param ka The acceleration gain. + */ + public ArmFF(double ks, double kg, double kv, double ka) { + this.ks = ks; + this.kg = kg; + this.kv = kv; + this.ka = ka; + } + + /** + * Creates a new ArmFF with the specified gains. Acceleration gain is defaulted to zero. + * Units of the gain values will dictate units of the computed feedforward. + * + * @param ks The static gain. + * @param kg The gravity gain. + * @param kv The velocity gain. + */ + public ArmFF(double ks, double kg, double kv) { + this(ks, kg, kv, 0); + } + + /** + * Calculates the feedforward from the gains and setpoints. + * + * @param positionRadians The position (angle) setpoint. This angle should be measured from the + * horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If + * your encoder does not follow this convention, an offset should be added. + * @param velocityRadPerSec The velocity setpoint. + * @param accelRadPerSecSquared The acceleration setpoint. + * @return The computed feedforward. + */ + public double calculate( + double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared) { + return ks * Math.signum(velocityRadPerSec) + + kg * Math.cos(positionRadians) + + kv * velocityRadPerSec + + ka * accelRadPerSecSquared; + } + + /** + * Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be + * zero). + * + * @param positionRadians The position (angle) setpoint. This angle should be measured from the + * horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If + * your encoder does not follow this convention, an offset should be added. + * @param velocity The velocity setpoint. + * @return The computed feedforward. + */ + public double calculate(double positionRadians, double velocity) { + return calculate(positionRadians, velocity, 0); + } + + // Rearranging the main equation from the calculate() method yields the + // formulas for the methods below: + + /** + * Calculates the maximum achievable velocity given a maximum voltage supply, a position, and an + * acceleration. Useful for ensuring that velocity and acceleration constraints for a trapezoidal + * profile are simultaneously achievable - enter the acceleration constraint, and this will give + * you a simultaneously-achievable velocity constraint. + * + * @param maxVoltage The maximum voltage that can be supplied to the arm. + * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if + * the provided angle is 0, the arm should be parallel with the floor). If your encoder does + * not follow this convention, an offset should be added. + * @param acceleration The acceleration of the arm. + * @return The maximum possible velocity at the given acceleration and angle. + */ + public double maxAchievableVelocity(double maxVoltage, double angle, double acceleration) { + // Assume max velocity is positive + return (maxVoltage - ks - Math.cos(angle) * kg - acceleration * ka) / kv; + } + + /** + * Calculates the minimum achievable velocity given a maximum voltage supply, a position, and an + * acceleration. Useful for ensuring that velocity and acceleration constraints for a trapezoidal + * profile are simultaneously achievable - enter the acceleration constraint, and this will give + * you a simultaneously-achievable velocity constraint. + * + * @param maxVoltage The maximum voltage that can be supplied to the arm. + * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if + * the provided angle is 0, the arm should be parallel with the floor). If your encoder does + * not follow this convention, an offset should be added. + * @param acceleration The acceleration of the arm. + * @return The minimum possible velocity at the given acceleration and angle. + */ + public double minAchievableVelocity(double maxVoltage, double angle, double acceleration) { + // Assume min velocity is negative, ks flips sign + return (-maxVoltage + ks - Math.cos(angle) * kg - acceleration * ka) / kv; + } + + /** + * Calculates the maximum achievable acceleration given a maximum voltage supply, a position, and + * a velocity. Useful for ensuring that velocity and acceleration constraints for a trapezoidal + * profile are simultaneously achievable - enter the velocity constraint, and this will give you a + * simultaneously-achievable acceleration constraint. + * + * @param maxVoltage The maximum voltage that can be supplied to the arm. + * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if + * the provided angle is 0, the arm should be parallel with the floor). If your encoder does + * not follow this convention, an offset should be added. + * @param velocity The velocity of the arm. + * @return The maximum possible acceleration at the given velocity. + */ + public double maxAchievableAcceleration(double maxVoltage, double angle, double velocity) { + return (maxVoltage - ks * Math.signum(velocity) - Math.cos(angle) * kg - velocity * kv) / ka; + } + + /** + * Calculates the minimum achievable acceleration given a maximum voltage supply, a position, and + * a velocity. Useful for ensuring that velocity and acceleration constraints for a trapezoidal + * profile are simultaneously achievable - enter the velocity constraint, and this will give you a + * simultaneously-achievable acceleration constraint. + * + * @param maxVoltage The maximum voltage that can be supplied to the arm. + * @param angle The angle of the arm. This angle should be measured from the horizontal (i.e. if + * the provided angle is 0, the arm should be parallel with the floor). If your encoder does + * not follow this convention, an offset should be added. + * @param velocity The velocity of the arm. + * @return The minimum possible acceleration at the given velocity. + */ + public double minAchievableAcceleration(double maxVoltage, double angle, double velocity) { + return maxAchievableAcceleration(-maxVoltage, angle, velocity); + } + + public double getS() { + return ks; + } + + public double getG() { + return kg; + } + + public double getV() { + return kv; + } + + public double getA() { + return ka; + } + + public void setS(double ks) { + this.ks = ks; + } + + public void setG(double kg) { + this.kg = kg; + } + + public void setV(double kv) { + this.kv = kv; + } + + public void setA(double ka) { + this.ka = ka; + } +} diff --git a/src/main/java/frc/robot/commands/arm/ArmPID.java b/src/main/java/frc/robot/commands/arm/ArmPID.java new file mode 100644 index 0000000..4cced28 --- /dev/null +++ b/src/main/java/frc/robot/commands/arm/ArmPID.java @@ -0,0 +1,388 @@ +// 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. + +// Edited by Team 178 for resettable m_totalError + +package frc.robot.commands.arm; + +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.util.sendable.SendableRegistry; + +/** Implements a PID control loop. */ +public class ArmPID implements Sendable, AutoCloseable { + private static int instances; + + // Factor for "proportional" control + private double m_kp; + + // Factor for "integral" control + private double m_ki; + + // Factor for "derivative" control + private double m_kd; + + // The period (in seconds) of the loop that calls the controller + private final double m_period; + + private double m_maximumIntegral = 1.0; + + private double m_minimumIntegral = -1.0; + + private double m_maximumInput; + + private double m_minimumInput; + + // Do the endpoints wrap around? e.g. Absolute encoder + private boolean m_continuous; + + // The error at the time of the most recent call to calculate() + private double m_positionError; + private double m_velocityError; + + // The error at the time of the second-most-recent call to calculate() (used to compute velocity) + private double m_prevError; + + // The sum of the errors for use in the integral calc + private double m_totalError; + + // The error that is considered at setpoint. + private double m_positionTolerance = 0.05; + private double m_velocityTolerance = Double.POSITIVE_INFINITY; + + private double m_setpoint; + private double m_measurement; + + private boolean m_haveMeasurement; + private boolean m_haveSetpoint; + + /** + * Allocates a PIDController with the given constants for kp, ki, and kd and a default period of + * 0.02 seconds. + * + * @param kp The proportional coefficient. + * @param ki The integral coefficient. + * @param kd The derivative coefficient. + */ + public ArmPID(double kp, double ki, double kd) { + this(kp, ki, kd, 0.02); + } + + /** + * Allocates a PIDController with the given constants for kp, ki, and kd. + * + * @param kp The proportional coefficient. + * @param ki The integral coefficient. + * @param kd The derivative coefficient. + * @param period The period between controller updates in seconds. Must be non-zero and positive. + */ + public ArmPID(double kp, double ki, double kd, double period) { + m_kp = kp; + m_ki = ki; + m_kd = kd; + + if (period <= 0) { + throw new IllegalArgumentException("Controller period must be a non-zero positive number!"); + } + m_period = period; + + instances++; + SendableRegistry.addLW(this, "PIDController", instances); + + MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances); + } + + @Override + public void close() { + SendableRegistry.remove(this); + } + + /** + * Sets the PID Controller gain parameters. + * + *

Set the proportional, integral, and differential coefficients. + * + * @param kp The proportional coefficient. + * @param ki The integral coefficient. + * @param kd The derivative coefficient. + */ + public void setPID(double kp, double ki, double kd) { + m_kp = kp; + m_ki = ki; + m_kd = kd; + } + + /** + * Sets the Proportional coefficient of the PID controller gain. + * + * @param kp proportional coefficient + */ + public void setP(double kp) { + m_kp = kp; + } + + /** + * Sets the Integral coefficient of the PID controller gain. + * + * @param ki integral coefficient + */ + public void setI(double ki) { + m_ki = ki; + } + + /** + * Sets the Differential coefficient of the PID controller gain. + * + * @param kd differential coefficient + */ + public void setD(double kd) { + m_kd = kd; + } + + /** + * Get the Proportional coefficient. + * + * @return proportional coefficient + */ + public double getP() { + return m_kp; + } + + /** + * Get the Integral coefficient. + * + * @return integral coefficient + */ + public double getI() { + return m_ki; + } + + /** + * Get the Differential coefficient. + * + * @return differential coefficient + */ + public double getD() { + return m_kd; + } + + /** + * Returns the period of this controller. + * + * @return the period of the controller. + */ + public double getPeriod() { + return m_period; + } + + /** + * Returns the position tolerance of this controller. + * + * @return the position tolerance of the controller. + */ + public double getPositionTolerance() { + return m_positionTolerance; + } + + /** + * Returns the velocity tolerance of this controller. + * + * @return the velocity tolerance of the controller. + */ + public double getVelocityTolerance() { + return m_velocityTolerance; + } + + /** + * Sets the setpoint for the PIDController. + * + * @param setpoint The desired setpoint. + */ + public void setSetpoint(double setpoint) { + m_setpoint = setpoint; + m_haveSetpoint = true; + + if (m_continuous) { + double errorBound = (m_maximumInput - m_minimumInput) / 2.0; + m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound); + } else { + m_positionError = m_setpoint - m_measurement; + } + + m_velocityError = (m_positionError - m_prevError) / m_period; + } + + /** + * Returns the current setpoint of the PIDController. + * + * @return The current setpoint. + */ + public double getSetpoint() { + return m_setpoint; + } + + /** + * Returns true if the error is within the tolerance of the setpoint. + * + *

This will return false until at least one input value has been computed. + * + * @return Whether the error is within the acceptable bounds. + */ + public boolean atSetpoint() { + return m_haveMeasurement + && m_haveSetpoint + && Math.abs(m_positionError) < m_positionTolerance + && Math.abs(m_velocityError) < m_velocityTolerance; + } + + /** + * Enables continuous input. + * + *

Rather then using the max and min input range as constraints, it considers them to be the + * same point and automatically calculates the shortest route to the setpoint. + * + * @param minimumInput The minimum value expected from the input. + * @param maximumInput The maximum value expected from the input. + */ + public void enableContinuousInput(double minimumInput, double maximumInput) { + m_continuous = true; + m_minimumInput = minimumInput; + m_maximumInput = maximumInput; + } + + /** Disables continuous input. */ + public void disableContinuousInput() { + m_continuous = false; + } + + /** + * Returns true if continuous input is enabled. + * + * @return True if continuous input is enabled. + */ + public boolean isContinuousInputEnabled() { + return m_continuous; + } + + /** + * Sets the minimum and maximum values for the integrator. + * + *

When the cap is reached, the integrator value is added to the controller output rather than + * the integrator value times the integral gain. + * + * @param minimumIntegral The minimum value of the integrator. + * @param maximumIntegral The maximum value of the integrator. + */ + public void setIntegratorRange(double minimumIntegral, double maximumIntegral) { + m_minimumIntegral = minimumIntegral; + m_maximumIntegral = maximumIntegral; + } + + /** + * Sets the error which is considered tolerable for use with atSetpoint(). + * + * @param positionTolerance Position error which is tolerable. + */ + public void setTolerance(double positionTolerance) { + setTolerance(positionTolerance, Double.POSITIVE_INFINITY); + } + + /** + * Sets the error which is considered tolerable for use with atSetpoint(). + * + * @param positionTolerance Position error which is tolerable. + * @param velocityTolerance Velocity error which is tolerable. + */ + public void setTolerance(double positionTolerance, double velocityTolerance) { + m_positionTolerance = positionTolerance; + m_velocityTolerance = velocityTolerance; + } + + /** + * Returns the difference between the setpoint and the measurement. + * + * @return The error. + */ + public double getPositionError() { + return m_positionError; + } + + /** + * Returns the velocity error. + * + * @return The velocity error. + */ + public double getVelocityError() { + return m_velocityError; + } + + /** + * Returns the next output of the PID controller. + * + * @param measurement The current measurement of the process variable. + * @param setpoint The new setpoint of the controller. + * @return The next controller output. + */ + public double calculate(double measurement, double setpoint) { + m_setpoint = setpoint; + m_haveSetpoint = true; + return calculate(measurement); + } + + /** + * Returns the next output of the PID controller. + * + * @param measurement The current measurement of the process variable. + * @return The next controller output. + */ + public double calculate(double measurement) { + m_measurement = measurement; + m_prevError = m_positionError; + m_haveMeasurement = true; + + if (m_continuous) { + double errorBound = (m_maximumInput - m_minimumInput) / 2.0; + m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound); + } else { + m_positionError = m_setpoint - m_measurement; + } + + m_velocityError = (m_positionError - m_prevError) / m_period; + + if (m_ki != 0) { + m_totalError = + MathUtil.clamp( + m_totalError + m_positionError * m_period, + m_minimumIntegral / m_ki, + m_maximumIntegral / m_ki); + } + + return m_kp * m_positionError + m_ki * m_totalError + m_kd * m_velocityError; + } + + /** Resets the previous error and the integral term. */ + public void reset() { + m_positionError = 0; + m_prevError = 0; + m_totalError = 0; + m_velocityError = 0; + m_haveMeasurement = false; + } + + public void resetIntegralError() { + m_totalError = 0; + } + + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("PIDController"); + builder.addDoubleProperty("p", this::getP, this::setP); + builder.addDoubleProperty("i", this::getI, this::setI); + builder.addDoubleProperty("d", this::getD, this::setD); + builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint); + } +} diff --git a/src/main/java/frc/robot/commands/arm/ArmPosition.java b/src/main/java/frc/robot/commands/arm/ArmPosition.java new file mode 100644 index 0000000..29acd7c --- /dev/null +++ b/src/main/java/frc/robot/commands/arm/ArmPosition.java @@ -0,0 +1,26 @@ +package frc.robot.commands.arm; + +public enum ArmPosition { + //! These values are not adjusted + HOME(309.897908, 342.843705), + SUBSTATION(240.671931, 293.881183), + // HIGH(2.976432, 3.154062), + // LOW(3.587507, 4.466632), + BACK(290, 315); + + private double lowerSetpoint; + private double upperSetpoint; + + private ArmPosition(double lowerSetpoint, double upperSetpoint) { + this.lowerSetpoint = lowerSetpoint; + this.upperSetpoint = upperSetpoint; + } + + public double getLowerSetpoint() { + return lowerSetpoint; + } + + public double getUpperSetpoint() { + return upperSetpoint; + } +} diff --git a/src/main/java/frc/robot/subsystems/Arm.java b/src/main/java/frc/robot/subsystems/Arm.java new file mode 100644 index 0000000..4a6c4d9 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Arm.java @@ -0,0 +1,237 @@ +package frc.robot.subsystems; + +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkMax.IdleMode; +import com.revrobotics.CANSparkMaxLowLevel.MotorType; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj.DutyCycleEncoder; +import edu.wpi.first.wpilibj.Preferences; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.ArmConstants; +import frc.robot.commands.arm.ArmFF; +import frc.robot.commands.arm.ArmPID; +import frc.robot.commands.arm.ArmPosition; + +public class Arm extends SubsystemBase { + private CANSparkMax m_lowerMotor; + private CANSparkMax m_upperMotor; + + private DutyCycleEncoder m_lowerEncoder; + private DutyCycleEncoder m_upperEncoder; + + private ArmPID m_lowerPIDController; + private ArmPID m_upperPIDController; + private ArmFF m_lowerFFController; + private ArmFF m_upperFFController; + + private DigitalInput m_lowerLimit; + private DigitalInput m_upperLimit; + + private ArmPosition m_armPosition; + + private boolean toSetpoint; + + public Arm() { + ArmConstants.initArmPreferences(); + Preferences.initDouble("kLowerTestOutput", 0.1); + Preferences.initDouble("kUpperTestOutput", 0.1); + + m_lowerMotor = new CANSparkMax(ArmConstants.kLowerSparkPort, MotorType.kBrushless); + m_lowerEncoder = new DutyCycleEncoder(ArmConstants.kLowerEncoderChannel); + m_lowerLimit = new DigitalInput(ArmConstants.kLowerLimitChannel); + m_lowerPIDController = new ArmPID( + ArmConstants.getKLowerP(), + ArmConstants.getKLowerI(), + ArmConstants.getKLowerD() + ); + m_lowerFFController = new ArmFF( + ArmConstants.getKLowerS(), + ArmConstants.getKLowerG(), + ArmConstants.getKLowerV(), + ArmConstants.getKLowerA() + ); + + m_upperMotor = new CANSparkMax(ArmConstants.kUpperSparkPort, MotorType.kBrushless); + m_upperEncoder = new DutyCycleEncoder(ArmConstants.kUpperEncoderChannel); + m_upperLimit = new DigitalInput(ArmConstants.kUpperLimitChannel); + m_upperPIDController = new ArmPID( + ArmConstants.getKUpperP(), + ArmConstants.getKUpperI(), + ArmConstants.getKUpperD() + ); + m_upperFFController = new ArmFF( + ArmConstants.getKUpperS(), + ArmConstants.getKUpperG(), + ArmConstants.getKUpperV(), + ArmConstants.getKUpperA() + ); + + setArmPosition(ArmPosition.HOME); + + m_lowerMotor.restoreFactoryDefaults(); + m_upperMotor.restoreFactoryDefaults(); + + //! double check + m_lowerMotor.setInverted(false); + m_upperMotor.setInverted(false); + + setBrake(); + + //! double check how encoder class works + // m_lowerEncoder.reset(); + // m_upperEncoder.reset(); + + toSetpoint = false; + + } + + public void updateToPreferences() { + m_lowerPIDController.setP(ArmConstants.getKLowerP()); + m_lowerPIDController.setI(ArmConstants.getKLowerI()); + m_lowerPIDController.setD(ArmConstants.getKLowerD()); + + m_lowerFFController.setS(ArmConstants.getKLowerS()); + m_lowerFFController.setG(ArmConstants.getKLowerG()); + m_lowerFFController.setV(ArmConstants.getKLowerV()); + m_lowerFFController.setA(ArmConstants.getKLowerA()); + + m_upperPIDController.setP(ArmConstants.getKUpperP()); + m_upperPIDController.setI(ArmConstants.getKUpperI()); + m_upperPIDController.setD(ArmConstants.getKUpperD()); + + m_upperFFController.setS(ArmConstants.getKUpperS()); + m_upperFFController.setG(ArmConstants.getKUpperG()); + m_upperFFController.setV(ArmConstants.getKUpperV()); + m_upperFFController.setA(ArmConstants.getKUpperA()); + } + + public double getLowerPosition() { + return m_lowerEncoder.getAbsolutePosition() * 360; + } + + public double getUpperPosition() { + return m_upperEncoder.getAbsolutePosition() * 360; + } + + public void setBrake() { + m_lowerMotor.setIdleMode(IdleMode.kBrake); + m_upperMotor.setIdleMode(IdleMode.kBrake); + } + + public void setCoast() { + m_lowerMotor.setIdleMode(IdleMode.kCoast); + m_upperMotor.setIdleMode(IdleMode.kCoast); + } + + public void setArmPosition(ArmPosition armPosition) { + m_armPosition = armPosition; + m_lowerPIDController.resetIntegralError(); + m_upperPIDController.resetIntegralError(); + m_lowerPIDController.setSetpoint(m_armPosition.getLowerSetpoint()); + m_upperPIDController.setSetpoint(m_armPosition.getUpperSetpoint()); + } + + public CommandBase runLowerTest() { + return runOnce(() -> { + m_lowerMotor.setVoltage(Preferences.getDouble("kLowerTestOutput", 0)); + System.out.println("Lower motor test speed on."); + }); + } + + public CommandBase runUpperTest() { + return runOnce(() -> { + m_upperMotor.setVoltage(Preferences.getDouble("kUpperTestOutput", 0)); + System.out.println("Upper motor test speed on."); + }); + } + + public CommandBase runCutMotors() { + return runOnce(() -> { + m_lowerMotor.setVoltage(0); + m_upperMotor.setVoltage(0); + System.out.println("Arm motors off."); + }); + } + + public CommandBase runToSetpoint() { + return runOnce(() -> { + toSetpoint = true; + System.out.println("On setpoint."); + }); + } + + public CommandBase runGetOffSetpoint() { + return runOnce(() -> { + toSetpoint = false; + m_lowerMotor.setVoltage(0); + m_upperMotor.setVoltage(0); + System.out.println("Off setpoint."); + }); + } + + public CommandBase runSetArmPosition(ArmPosition newPosition) { + return runOnce(() -> { + setArmPosition(newPosition); + }); + } + + public CommandBase runBumpLower(double bump) { + return run(() -> { + m_lowerPIDController.resetIntegralError(); + m_lowerPIDController.setSetpoint(m_lowerPIDController.getSetpoint() + bump); + }); + } + + public CommandBase runBumpUpper(double bump) { + return run(() -> { + m_upperPIDController.resetIntegralError(); + m_upperPIDController.setSetpoint(m_upperPIDController.getSetpoint() + bump); + }); + } + + @Override + public void periodic() { + updateToPreferences(); + SmartDashboard.putNumber("Lower Raw Position", m_lowerEncoder.getAbsolutePosition()); + SmartDashboard.putNumber("Upper Raw Position", m_upperEncoder.getAbsolutePosition()); + SmartDashboard.putNumber("Lower Position", getLowerPosition()); + SmartDashboard.putNumber("Upper Position", getUpperPosition()); + SmartDashboard.putNumber("Lower Pos Offset", m_lowerEncoder.getPositionOffset()); + SmartDashboard.putNumber("Upper Pos Offset", m_upperEncoder.getPositionOffset()); + + SmartDashboard.putBoolean("Lower Home", m_lowerLimit.get()); + SmartDashboard.putBoolean("Upper Home", m_upperLimit.get()); + + SmartDashboard.putNumber("Lower Setpoint", m_lowerPIDController.getSetpoint()); + SmartDashboard.putNumber("Upper Setpoint", m_upperPIDController.getSetpoint()); + + double lowerPIDOutput = m_lowerPIDController.calculate(getLowerPosition()); + double upperPIDOutput = m_upperPIDController.calculate(getUpperPosition()); + + double lowerRadians = Units.degreesToRadians(m_lowerPIDController.getSetpoint() - ArmConstants.kLowerOffset); + double upperRadians = Units.degreesToRadians(m_upperPIDController.getSetpoint() - ArmConstants.kUpperOffset); + SmartDashboard.putNumber("LowerRadians", Math.cos(Units.degreesToRadians(getLowerPosition() - ArmConstants.kLowerOffset))); + SmartDashboard.putNumber("UpperRadians", Math.cos(Units.degreesToRadians(getUpperPosition() - ArmConstants.kUpperOffset))); + double lowerFFOutput = m_lowerFFController.calculate(lowerRadians, 0); + double upperFFOutput = m_upperFFController.calculate(upperRadians, 0); + + SmartDashboard.putNumber("Lower PID Output", lowerPIDOutput); + SmartDashboard.putNumber("Upper PID Output", upperPIDOutput); + SmartDashboard.putNumber("Lower FF Output", lowerFFOutput); + SmartDashboard.putNumber("Upper FF Output", upperFFOutput); + + if(toSetpoint) { + m_lowerMotor.setVoltage(MathUtil.clamp(lowerPIDOutput + lowerFFOutput, -ArmConstants.kLowerMaxVolts, ArmConstants.kLowerMaxVolts)); + m_upperMotor.setVoltage(MathUtil.clamp(upperPIDOutput + upperFFOutput, -ArmConstants.kUpperMaxVolts, ArmConstants.kUpperMaxVolts)); + } + } + + + +} diff --git a/src/main/java/frc/robot/subsystems/Claw.java b/src/main/java/frc/robot/subsystems/Claw.java new file mode 100644 index 0000000..8fe528f --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Claw.java @@ -0,0 +1,24 @@ +package frc.robot.subsystems; + +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.Solenoid; +import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.ClawConstants; + +public class Claw extends SubsystemBase { + private Solenoid m_solenoid; + + public Claw() { + m_solenoid = new Solenoid(PneumaticsModuleType.CTREPCM, ClawConstants.kSolenoidPort); + m_solenoid.set(false); + } + + public void toggleClaw() { + m_solenoid.toggle(); + } + + public CommandBase runToggleClaw() { + return runOnce(() -> toggleClaw()); + } +} diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json new file mode 100644 index 0000000..614dc3a --- /dev/null +++ b/vendordeps/Phoenix.json @@ -0,0 +1,423 @@ +{ + "fileName": "Phoenix.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.31.0+23.2.2", + "frcYear": 2023, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.31.0" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.31.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", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "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", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "23.2.2", + "libName": "CTRE_PhoenixTools", + "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.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", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "23.2.2", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "23.2.2", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "23.2.2", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "23.2.2", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "23.2.2", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "23.2.2", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "23.2.2", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "23.2.2", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "23.2.2", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..f2d0b7d --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,73 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2023.1.3", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2023.1.3" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2023.1.3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2023.1.3", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2023.1.3", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json new file mode 100644 index 0000000..bd535bf --- /dev/null +++ b/vendordeps/WPILibNewCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "1.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "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" + ] + } + ] +}