51 Commits

Author SHA1 Message Date
431c1c2f01 Minor change to add manual, again, just a proof of concept, don't use this 2025-02-21 20:51:46 -05:00
771bcc89e1 Rework done, only a proof of concept, shouldn't be used without a lot of free time 2025-02-21 20:39:03 -05:00
f57cf77200 elevator and manipulator work invidiually, not together 2025-02-20 18:57:39 -05:00
c48a53a0a5 stuff works more tuning 2025-02-20 17:40:16 -05:00
858c897aad added a few things to the shuffle board 2025-02-19 22:22:47 +00:00
1819f59657 added a reset 2025-02-19 18:28:17 +00:00
98ae2a4d94 Changed elevator and manip pivot to regular pid controllers 2025-02-19 18:23:41 +00:00
0522f7c579 testing from 2/18 2025-02-18 19:01:11 -05:00
f6aeec7c7e Corrected the elevator velocity converstion factor and added the controller reset in the right place 2025-02-18 18:33:10 +00:00
42d15ab101 More work tuning the elevator 2025-02-17 18:58:43 -05:00
aa6a0366e6 feeding vision into pose estimation 2025-02-17 03:20:28 -05:00
2e9f294cdb Prep for 2/17 meeting. Finished removing TrashMotion. 2025-02-17 05:11:38 +00:00
9fc597bd30 Many attempt at tuning Elevator values at 2/15 build session 2025-02-15 18:20:59 -05:00
5a53c5fe07 Merge branch 'main' of https://git.coldlightalchemist.com/Team_2648/2025_Robot_Code 2025-02-15 12:47:07 -05:00
ddcf64159f Robot PID testing 2025-02-15 12:46:23 -05:00
9497e216d7 beginning auto paths 2025-02-15 03:11:11 -05:00
9cc9b993eb global pose vision transformations 2025-02-15 02:48:28 -05:00
38dad2861d global apriltag coordinates 2025-02-15 01:48:58 -05:00
2275248f70 Random changes to try to make the robot work 2025-02-14 17:04:01 -05:00
187e7385c8 testing stuff day one 2025-02-11 19:10:01 -05:00
f0b7955faa working on dt offsets 2025-02-11 16:44:51 -05:00
aff9a4f2cb safe travels command and constants 2025-02-11 14:27:29 -05:00
619b3f4b7f manipulator pivot on controller pid 2025-02-11 09:15:19 -05:00
ed1ffe7044 manipulator and elevator constants 2025-02-11 00:55:28 -05:00
96ad0ba088 work on elevator manual, vision, and manipulator 2025-02-10 22:06:12 -05:00
56980d3772 removed velocity controllers on position mechanisms and added controller PID for elevator 2025-02-08 03:27:59 -05:00
6fa4377e52 removed algae beam break 2025-01-30 12:54:43 -05:00
89c1914d11 drivetrain odometry -> pose estimator 2025-01-30 04:14:57 -05:00
3af046f058 changing a bunch of constants and fixing stuff 2025-01-30 03:49:33 -05:00
34a547026d added vision class 2025-01-30 01:59:08 -05:00
0e91643b57 Merge branch 'kraken_swerve'
release the kraken
2025-01-27 21:38:03 -05:00
5fa4738b36 Added a few shuffle board things 2025-01-27 14:18:28 +00:00
ff3ecf6d1d Didnt commit everything for some reason 2025-01-26 19:31:38 +00:00
cef200a864 Renamed things for consistency, added a few methods 2025-01-26 19:28:49 +00:00
dff4d0e04f added spark configs to all subsystems, fixed a few formatting inconsistencies, added a TODO 2025-01-21 04:18:36 +00:00
9ab7ffad84 1,000 comments, reworked the climber pivot, removed indexer, added clamps on goToSetpoint methods 2025-01-21 03:56:00 +00:00
a96d96fecb Merge branch 'main' into kraken_swerve 2025-01-20 20:12:40 -05:00
edb95da65c Merge branch 'main' of https://git.coldlightalchemist.com/Team_2648/2025_Robot_Code 2025-01-20 20:02:53 -05:00
b90056f9ce Adding basic PathPlanner setup 2025-01-20 20:02:51 -05:00
ce7246114f Added lots of comments, also added a few simple methods as backup 2025-01-21 00:58:38 +00:00
198d105741 Adding AHRS from Studica to the drivetrain so the NavX is assumed to be used, also cleaned up some unused imports 2025-01-20 19:33:33 -05:00
8cbd9bb095 Kraken swerve based on Tyler's original work 2025-01-18 16:04:54 -05:00
4d9aa82520 Adding ArmSysID and some more configuration stuff 2025-01-18 15:00:53 -05:00
c1dddcace5 Resolving some issues related to the use of the CANcoder, and added some missing constants and instantiations for PIDControllers related to the Arm 2025-01-18 12:57:02 -05:00
ecf4916b93 Upgrading to 2025.2.1 2025-01-18 11:12:48 -05:00
91cd13f87a did small amounts of stuff. can't remember 2025-01-18 15:47:18 +00:00
5325920b42 Adjusting moveManipulator so it's not so...rough 2025-01-16 17:59:12 -05:00
d1d577f52f fixed a terrible formatting error 2025-01-16 19:52:38 +00:00
11a191440c added a smooth manipulator translation method 2025-01-16 19:46:20 +00:00
f4cfd2874b began adding elevator and arm methods 2025-01-16 15:26:54 +00:00
f391d1540b One more fix to resolve Noah's merge conflict for him 2025-01-15 02:24:19 +00:00
48 changed files with 2431 additions and 749 deletions

View File

@@ -0,0 +1,6 @@
{
"download": {
"localDir": "C:\\Users\\infin\\Downloads",
"serverTeam": "2648"
}
}

View File

@@ -0,0 +1,13 @@
{
"NetworkTables Settings": {
"mode": "Client (NT4)"
},
"transitory": {
"Shuffleboard": {
"Sensors Tab": {
"open": true
},
"open": true
}
}
}

1
.SysId/sysid.json Normal file
View File

@@ -0,0 +1 @@
{}

View File

@@ -1,24 +1,24 @@
Copyright (c) 2009-2024 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.
Copyright (c) 2009-2024 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.

View File

@@ -1,102 +1,104 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1"
}
java {
sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
}
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 = false
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 5.
dependencies {
annotationProcessor wpi.java.deps.wpilibAnnotations()
implementation wpi.java.deps.wpilib()
implementation wpi.java.vendor.java()
roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio)
roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio)
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:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
}
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) } }
from sourceSets.main.allSource
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'
}
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
}
java {
sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
}
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'
deleteOldFiles = false // Change to true to delete files on roboRIO that no
// longer exist in deploy directory of this project
}
}
}
}
}
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 = false
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 5.
dependencies {
annotationProcessor wpi.java.deps.wpilibAnnotations()
implementation wpi.java.deps.wpilib()
implementation wpi.java.vendor.java()
roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio)
roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio)
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:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
}
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) } }
from sourceSets.main.allSource
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'
}

View File

@@ -1,7 +1,7 @@
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME
zipStorePath=permwrapper/dists
distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip
networkTimeout=10000
validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME
zipStorePath=permwrapper/dists

188
gradlew.bat vendored
View File

@@ -1,94 +1,94 @@
@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
@rem SPDX-License-Identifier: Apache-2.0
@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=.
@rem This is normally unused
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. 1>&2
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2
goto fail
:findJavaFromJavaHome
set JAVA_HOME=%JAVA_HOME:"=%
set JAVA_EXE=%JAVA_HOME%/bin/java.exe
if exist "%JAVA_EXE%" goto execute
echo. 1>&2
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2
goto fail
: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
@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
@rem SPDX-License-Identifier: Apache-2.0
@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=.
@rem This is normally unused
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. 1>&2
echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2
goto fail
:findJavaFromJavaHome
set JAVA_HOME=%JAVA_HOME:"=%
set JAVA_EXE=%JAVA_HOME%/bin/java.exe
if exist "%JAVA_EXE%" goto execute
echo. 1>&2
echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2
echo. 1>&2
echo Please set the JAVA_HOME variable in your environment to match the 1>&2
echo location of your Java installation. 1>&2
goto fail
: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

View File

@@ -1,30 +1,30 @@
import org.gradle.internal.os.OperatingSystem
pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2025'
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
}
}
}
Properties props = System.getProperties();
props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true");
import org.gradle.internal.os.OperatingSystem
pluginManagement {
repositories {
mavenLocal()
gradlePluginPortal()
String frcYear = '2025'
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
}
}
}
Properties props = System.getProperties();
props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true");

View File

@@ -0,0 +1,25 @@
{
"version": "2025.0",
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "Start to 30 Right"
}
},
{
"type": "named",
"data": {
"name": "Shoot Coral L4"
}
}
]
}
},
"resetOdom": true,
"folder": null,
"choreoAuto": false
}

View File

@@ -0,0 +1,49 @@
{
"version": "2025.0",
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "Start to 30 Right"
}
},
{
"type": "named",
"data": {
"name": "Shoot Coral L4"
}
},
{
"type": "path",
"data": {
"pathName": "30 Right to HP"
}
},
{
"type": "named",
"data": {
"name": "Collect Coral"
}
},
{
"type": "path",
"data": {
"pathName": "HP to 330 Left"
}
},
{
"type": "named",
"data": {
"name": "Shoot Coral L4"
}
}
]
}
},
"resetOdom": true,
"folder": null,
"choreoAuto": false
}

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,54 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 5.289041095890411,
"y": 2.9732020547945206
},
"prevControl": null,
"nextControl": {
"x": 5.950171232876712,
"y": 1.6208904109589037
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 1.4424657534246574,
"y": 0.7944777397260271
},
"prevControl": {
"x": 2.389083904109589,
"y": 2.5374571917808213
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": 54.162347045721745
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": 120.96375653207336
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,61 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 4.988527397260274,
"y": 5.257106164383561
},
"prevControl": null,
"nextControl": {
"x": 5.649657534252619,
"y": 6.474186643842743
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 1.3072345890410957,
"y": 7.135316780821918
},
"prevControl": {
"x": 2.1636986301369863,
"y": 6.188698630136986
},
"nextControl": null,
"isLocked": false,
"linkedName": "HP Left Position"
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [
{
"name": "HP Pickup",
"waypointRelativePos": 0.20476190476190542,
"endWaypointRelativePos": null,
"command": null
}
],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": -53.97262661489646
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": -120.06858282186238
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,66 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 3.6061643835666786,
"y": 5.031720890416444
},
"prevControl": null,
"nextControl": {
"x": 3.065239726031196,
"y": 5.647773972598556
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 1.2510679859194649,
"y": 7.0812357195448
},
"prevControl": {
"x": 1.6678510274010594,
"y": 6.6394691780780075
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [
{
"waypointRelativePos": 0.498997995991984,
"rotationDegrees": -52.46519085612145
}
],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [
{
"name": "HP Pickup",
"waypointRelativePos": 0.16666666666666663,
"endWaypointRelativePos": null,
"command": null
}
],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": -53.98486432191523
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": -59.99999999999999
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,61 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 1.3072345890410957,
"y": 7.135316780821918
},
"prevControl": null,
"nextControl": {
"x": 2.5994434931506847,
"y": 6.909931506849315
},
"isLocked": false,
"linkedName": "HP Left Position"
},
{
"anchor": {
"x": 3.973766447368421,
"y": 5.246957236842105
},
"prevControl": {
"x": 3.6582270638067773,
"y": 5.772856209444845
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [
{
"name": "Lift L4",
"waypointRelativePos": 0.5,
"endWaypointRelativePos": null,
"command": null
}
],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": -59.69923999693802
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": -53.97262661489646
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,61 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 7.602996575342465,
"y": 2.0115582191780823
},
"prevControl": null,
"nextControl": {
"x": 6.491095890410959,
"y": 1.9965325342465756
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 5.289041095890411,
"y": 2.9882277397260277
},
"prevControl": {
"x": 6.130479452054795,
"y": 2.11673801369863
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [
{
"name": "Lift L4",
"waypointRelativePos": 0.7142857142857124,
"endWaypointRelativePos": null,
"command": null
}
],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": 120.25643716352937
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": 90.0
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,61 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 7.587970890410959,
"y": 6.143621575342466
},
"prevControl": null,
"nextControl": {
"x": 6.385916095890411,
"y": 6.158647260273973
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 4.988527397260274,
"y": 5.227054794520548
},
"prevControl": {
"x": 5.574529109589041,
"y": 6.098544520547945
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [
{
"name": "Lift L4",
"waypointRelativePos": 0.4547619047619047,
"endWaypointRelativePos": null,
"command": null
}
],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 4.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": -121.60750224624898
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": -90.0
},
"useDefaultConstraints": true
}

View File

@@ -0,0 +1,32 @@
{
"robotWidth": 0.8763,
"robotLength": 0.8763,
"holonomicMode": true,
"pathFolders": [],
"autoFolders": [],
"defaultMaxVel": 4.0,
"defaultMaxAccel": 4.0,
"defaultMaxAngVel": 540.0,
"defaultMaxAngAccel": 720.0,
"defaultNominalVoltage": 12.0,
"robotMass": 48.35,
"robotMOI": 6.883,
"robotTrackwidth": 0.546,
"driveWheelRadius": 0.038,
"driveGearing": 4.29,
"maxDriveSpeed": 5.45,
"driveMotorType": "krakenX60",
"driveCurrentLimit": 65.0,
"wheelCOF": 1.1,
"flModuleX": 0.31115,
"flModuleY": 0.31115,
"frModuleX": 0.31115,
"frModuleY": -0.31115,
"blModuleX": -0.31115,
"blModuleY": 0.31115,
"brModuleX": -0.31115,
"brModuleY": -0.31115,
"bumperOffsetX": 0.0,
"bumperOffsetY": 0.0,
"robotFeatures": []
}

View File

@@ -4,21 +4,34 @@
package frc.robot;
import frc.robot.constants.ManipulatorPivotConstants;
import frc.robot.constants.ClimberPivotConstants;
import frc.robot.constants.ElevatorConstants;
import frc.robot.constants.OIConstants;
import frc.robot.subsystems.Arm;
import frc.robot.constants.ElevatorConstants.ElevatorPositions;
import frc.robot.subsystems.ManipulatorPivot;
import frc.robot.subsystems.Vision;
import frc.robot.subsystems.ClimberPivot;
import frc.robot.subsystems.ClimberRollers;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Elevator;
import frc.robot.subsystems.Indexer;
import frc.robot.subsystems.Manipulator;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.PrintCommand;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
public class RobotContainer {
private Arm arm;
private ClimberPivot climberPivot;
private ClimberRollers climberRollers;
@@ -26,42 +39,59 @@ public class RobotContainer {
private Drivetrain drivetrain;
private Elevator elevator;
private Indexer indexer;
//private ElevatorSysID elevator;
private Manipulator manipulator;
private ManipulatorPivot manipulatorPivot;
private CommandXboxController driver;
private CommandXboxController operator;
public RobotContainer() {
arm = new Arm();
private SendableChooser<Command> autoChooser;
private Vision vision;
public RobotContainer() {
climberPivot = new ClimberPivot();
climberRollers = new ClimberRollers();
manipulator = new Manipulator();
//vision = new Vision(drivetrain::getGyroValue);
drivetrain = new Drivetrain();
elevator = new Elevator();
elevator = new Elevator(manipulator::getAlgaePhotoswitch);
//elevator = new ElevatorSysID();
indexer = new Indexer();
manipulator = new Manipulator();
manipulatorPivot = new ManipulatorPivot();
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
operator = new CommandXboxController(OIConstants.kOperatorControllerPort);
autoChooser = AutoBuilder.buildAutoChooser();
configureButtonBindings();
//elevatorSysIDBindings();
configureNamedCommands();
configureShuffleboard();
}
private void configureButtonBindings() {
arm.setDefaultCommand(
arm.goToSetpoint(0, 1)
);
/*private void elevatorSysIDBindings() {
elevator.setDefaultCommand(elevator.maintainPosition());
operator.a().whileTrue(elevator.sysIdQuasistatic(Direction.kForward));
operator.b().whileTrue(elevator.sysIdQuasistatic(Direction.kReverse));
operator.x().whileTrue(elevator.sysIdDynamic(Direction.kForward));
operator.y().whileTrue(elevator.sysIdDynamic(Direction.kReverse));
}*/
private void configureButtonBindings() {
//Default commands
climberPivot.setDefaultCommand(
climberPivot.goToAngle(0, 1)
climberPivot.runPivot(0)
);
climberRollers.setDefaultCommand(
@@ -76,47 +106,301 @@ public class RobotContainer {
() -> true
)
);
elevator.setDefaultCommand(
elevator.runElevator(operator::getLeftY)
);
indexer.setDefaultCommand(
indexer.runIndexer(0)
manipulatorPivot.setDefaultCommand(
manipulatorPivot.maintainPosition()
);
manipulator.setDefaultCommand(
manipulator.runManipulator(0)
manipulator.runUntilCollected(
() -> 0
)
);
//Driver inputs
driver.start().whileTrue(
drivetrain.setXCommand()
);
driver.rightTrigger().whileTrue(
manipulator.runManipulator(1)
manipulator.runManipulator(() -> 1, true)
);
driver.leftTrigger().whileTrue(
manipulator.runUntilCollected(() -> 0.75)
);
driver.start().and(driver.back()).onTrue(
startingConfig()
);
driver.povDown().whileTrue(climberPivot.runPivot(-0.5));
driver.povUp().whileTrue(climberPivot.runPivot(0.5));
driver.povLeft().whileTrue(climberRollers.runRoller(0.5));
driver.povRight().whileTrue(climberRollers.runRoller(-0.5));
//Operator inputs
operator.povUp().onTrue(
elevator.goToSetpoint(0, 0)
safeMoveManipulator(
ElevatorPositions.kL4,
ManipulatorPivotConstants.kL4Position
)
);
operator.povRight().onTrue(
elevator.goToSetpoint(0, 0)
safeMoveManipulator(
ElevatorPositions.kL3,
ManipulatorPivotConstants.kL3Position
)
);
operator.povLeft().onTrue(
elevator.goToSetpoint(0, 0)
safeMoveManipulator(
ElevatorPositions.kL2,
ManipulatorPivotConstants.kL2Position
)
);
operator.povDown().onTrue(
elevator.goToSetpoint(0, 0)
safeMoveManipulator(
ElevatorPositions.kL1,
ManipulatorPivotConstants.kL1Position
)
);
operator.a().onTrue(
coralIntakeRoutine()
);
operator.x().onTrue(
algaeIntakeRoutine(true)
);
operator.b().onTrue(
algaeIntakeRoutine(false)
);
operator.y().onTrue(
elevator.setTargetPosition(ElevatorPositions.kL2)
);
new Trigger(() -> Math.abs(MathUtil.applyDeadband(operator.getLeftY(), .05)) > .05).onTrue(
elevator.runManualElevator(operator::getLeftY)
);
}
private void configureNamedCommands() {
NamedCommands.registerCommand("Drivetrain Set X", drivetrain.setXCommand());
}
//creates tabs and transforms them on the shuffleboard
private void configureShuffleboard() {
ShuffleboardTab autoTab = Shuffleboard.getTab(OIConstants.kAutoTab);
ShuffleboardTab sensorTab = Shuffleboard.getTab(OIConstants.kSensorsTab);
Shuffleboard.selectTab(OIConstants.kAutoTab);
autoTab.add("Auto Selection", autoChooser)
.withSize(2, 1)
.withPosition(0, 0)
.withWidget(BuiltInWidgets.kComboBoxChooser);
sensorTab.addDouble("Elevator Position", elevator::getEncoderPosition)
.withSize(2, 1)
.withPosition(0, 0)
.withWidget(BuiltInWidgets.kGraph);
sensorTab.addDouble("Manipulator Position", manipulatorPivot::getEncoderPosition)
.withSize(2, 1)
.withPosition(2, 0)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addDouble("Climber Pivot Position", climberPivot::getEncoderPosition)
.withSize(2, 1)
.withPosition(2, 1)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addDouble("gyro angle", drivetrain::getGyroValue)
.withSize(2, 1)
.withPosition(0, 1)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addBoolean("Coral Sensor", manipulator::getCoralBeamBreak)
.withSize(1, 1)
.withPosition(4, 0)
.withWidget(BuiltInWidgets.kBooleanBox);
sensorTab.addBoolean("bottom limit switch", elevator::getBottomLimitSwitch)
.withSize(1, 1)
.withPosition(4, 1)
.withWidget(BuiltInWidgets.kBooleanBox);
sensorTab.addDouble("ElevMotor1", elevator::getMotor1)
.withWidget(BuiltInWidgets.kGraph);
sensorTab.addDouble("ElevMotor2", elevator::getMotor2)
.withWidget(BuiltInWidgets.kGraph);
sensorTab.addDouble("Elevator setpoint", elevator::getPIDSetpoint)
.withSize(1, 1)
.withPosition(5, 0)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addDouble("Elevator error", elevator::getPIDError)
.withSize(1, 1)
.withPosition(5, 1)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addDouble("manipulator output", manipulatorPivot::getPivotOutput);
sensorTab.addDouble("manipulator cg position", manipulatorPivot::getCGPosition);
}
public Command getAutonomousCommand() {
return autoChooser.getSelected();
}
/**
* Moves the elevator and arm to the coral intake position, then runs the manipulator until collected
* @return Moves the elevator and arm, then intakes coral
*/
@SuppressWarnings("unused")
private Command coralIntakeRoutine() {
return moveManipulator(
ElevatorPositions.kCoralIntake,
ManipulatorPivotConstants.kCoralIntakePosition
)
.andThen(manipulator.runUntilCollected(() -> .5));
}
/**
* Moves the elevator and arm to the constant setpoints and runs the manipulator until collected
*
* @param l2 Is the algae on L2? (True = L2, False = L3)
* @return Moves the elevator and arm then intakes algae
*/
@SuppressWarnings("unused")
private Command algaeIntakeRoutine(boolean l2) {
return moveManipulator(
l2 ? ElevatorPositions.kL2Algae : ElevatorPositions.kL3Algae,
l2 ? ManipulatorPivotConstants.kL2AlgaePosition : ManipulatorPivotConstants.kL3AlgaePosition
)
.andThen(manipulator.runUntilCollected(() -> 1));
}
/**
* Moves the elevator and arm in different order based on target positions
*
* @param elevatorPosition The target position of the elevator
* @param armPosition The target rotation of the arm
* @return Moves the elevator and arm to the setpoints using the most efficient path
*/
private Command moveManipulator(ElevatorPositions elevatorPosition, double armPosition) {
// If the elevator current and target positions are above the brace, or the arm current and target position is in
// front of the brace, move together
if ((elevator.isMotionSafe() && elevator.isMotionSafe(elevatorPosition.getPosition())) || (manipulatorPivot.isMotionSafe() && manipulatorPivot.isMotionSafe(armPosition))) {
return moveManipulatorUtil(elevatorPosition, armPosition, false, false);
// If the target position is behind the brace, and the arm is not behind the brace, move the arm to a safe position first,
// then the elevator, then the arm again
} else if (!manipulatorPivot.isMotionSafe(armPosition) && !manipulatorPivot.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, ManipulatorPivotConstants.kPivotSafeStowPosition, false, true)
.andThen(manipulatorPivot.goToSetpoint(() -> armPosition));
// If the target position is behind the brace, and the arm is behind the brace, move the elevator first, then the arm
} else if (!manipulatorPivot.isMotionSafe(armPosition) && manipulatorPivot.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, armPosition, true, true);
// If the arm is behind the brace, move the arm first, then the elevator
} else if (!manipulatorPivot.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, armPosition, false, true);
// Catch all command that's safe regardless of arm and elevator positions
} else {
return moveManipulatorUtil(elevatorPosition, ManipulatorPivotConstants.kPivotSafeStowPosition, false, true)
.andThen(manipulatorPivot.goToSetpoint(() -> armPosition));
}
}
/**
* Moves the elevator and arm in customizeable ways
*
* @param elevatorPosition The target elevator position
* @param armPosition The target arm position
* @param elevatorFirst Does the elevator move first? (True = Elevator first, False = Arm first)
* @param sequential Does the elevator and arm move separately? (True = .andThen, False = .alongWith)
* @return Moves the elevator and arm to the setpoints
*/
private Command moveManipulatorUtil(ElevatorPositions elevatorPosition, double armPosition, boolean elevatorFirst, boolean sequential) {
/*if (elevatorPosition <= ElevatorConstants.kBracePosition || elevatorPosition == 0) {
armPosition = MathUtil.clamp(
armPosition,
0,
ManipulatorPivotConstants.kRotationLimit
);
}*/
return Commands.either(
Commands.either(
elevator.setTargetPosition(elevatorPosition).andThen(
new WaitUntilCommand(elevator::atSetpoint),
manipulatorPivot.goToSetpoint(() -> armPosition)
),
elevator.setTargetPosition(elevatorPosition).alongWith(manipulatorPivot.goToSetpoint(() -> armPosition)),
() -> sequential
),
Commands.either(
manipulatorPivot.goToSetpoint(() -> armPosition).andThen(elevator.setTargetPosition(elevatorPosition)),
manipulatorPivot.goToSetpoint(() -> armPosition).alongWith(elevator.setTargetPosition(elevatorPosition)),
() -> sequential
),
() -> elevatorFirst
);
}
public Command getAutonomousCommand() {
return new PrintCommand("NO AUTO DEFINED");
@SuppressWarnings("unused")
private Command manipulatorSafeTravel(ElevatorPositions elevatorPosition, double armPosition, boolean isL4){
if(!isL4){
return Commands.sequence(
manipulatorPivot.goToSetpoint(() -> ManipulatorPivotConstants.kPivotSafeStowPosition),
elevator.setTargetPosition(elevatorPosition),
new WaitUntilCommand(elevator::atSetpoint),
manipulatorPivot.goToSetpoint(() -> armPosition));
}else{
return Commands.sequence(
manipulatorPivot.goToSetpoint(() -> ManipulatorPivotConstants.kPivotSafeStowPosition),
elevator.setTargetPosition(elevatorPosition),
new WaitUntilCommand(() -> elevator.getEncoderPosition() > ElevatorPositions.kL4Transition.getPosition()),
Commands.parallel(
manipulatorPivot.goToSetpoint(() -> armPosition),
elevator.setTargetPosition(elevatorPosition).andThen(new WaitUntilCommand(elevator::atSetpoint))
)
);
}
}
}
/**
* Moves the arm and elevator in a safe way.
*
* @param elevatorPosition The target position of the elevator
* @param armPosition The target rotation of the arm
* @return Moves the elevator and arm to the setpoints
*/
@SuppressWarnings("unused")
private Command safeMoveManipulator(ElevatorPositions elevatorPosition, double armPosition) {
return moveManipulatorUtil(elevatorPosition, ManipulatorPivotConstants.kPivotSafeStowPosition, false, true)
.andThen(manipulatorPivot.goToSetpoint(() -> armPosition));
}
@SuppressWarnings("unused")
private Command startingConfig() {
return moveManipulatorUtil(ElevatorPositions.kStartingPosition, 0, false, true)
.alongWith(climberPivot.climb(ClimberPivotConstants.kClimberStartingPosition, .1));
}
}

View File

@@ -1,10 +0,0 @@
package frc.robot.constants;
public class ArmConstants {
public static final int kArmMotorID = 0;
public static final int kCANcoderID = 0;
public static final double kEncoderConversionFactor = 0;
public static final double kArmMaxVelocity = 0;
}

View File

@@ -1,10 +1,18 @@
package frc.robot.constants;
import java.io.IOException;
import org.json.simple.parser.ParseException;
import com.pathplanner.lib.config.PIDConstants;
import com.pathplanner.lib.config.RobotConfig;
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
public class AutoConstants {
public static final double kMaxSpeedMetersPerSecond = 3;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
public static final double kMaxSpeedMetersPerSecond = 4;
public static final double kMaxAccelerationMetersPerSecondSquared = 4;
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
@@ -15,4 +23,21 @@ public class AutoConstants {
// Constraint for the motion profiled robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
// TODO This is a constant being managed like a static rewriteable variable
public static RobotConfig kRobotConfig;
public static final PPHolonomicDriveController kPPDriveController = new PPHolonomicDriveController(
new PIDConstants(kPXController, 0, 0),
new PIDConstants(kPYController, 0, 0)
);
static {
try {
kRobotConfig = RobotConfig.fromGUISettings();
} catch (IOException | ParseException e) {
System.err.println("FAILED TO READ ROBOTCONFIG, WAS THE CONFIG SET UP IN PATHPLANNER?");
e.printStackTrace();
}
}
}

View File

@@ -1,7 +1,9 @@
package frc.robot.constants;
import com.revrobotics.spark.config.SparkMaxConfig;
public class ClimberPivotConstants {
public static final int kPivotMotorID = 0;
public static final int kPivotMotorID = 10;
public static final int kClimberLimitSwitchID = 0;
@@ -10,4 +12,9 @@ public class ClimberPivotConstants {
public static final double kPIDControllerP = 0;
public static final double kPIDControllerI = 0;
public static final double kPIDControllerD = 0;
public static final double kClimberClimbPosition = 0;
public static final double kClimberStartingPosition = 0;
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
}

View File

@@ -1,5 +1,9 @@
package frc.robot.constants;
import com.revrobotics.spark.config.SparkMaxConfig;
public class ClimberRollersConstants {
public static final int kRollerMotorID = 0;
public static final int kRollerMotorID = 9;
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
}

View File

@@ -17,15 +17,15 @@ public class DrivetrainConstants {
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
// Chassis configuration
public static final double kTrackWidth = Units.inchesToMeters(26.5);
public static final double kTrackWidth = Units.inchesToMeters(24.5);
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = Units.inchesToMeters(26.5);
public static final double kWheelBase = Units.inchesToMeters(24.5);
// Angular offsets of the modules relative to the chassis in radians
public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2;
public static final double kFrontRightChassisAngularOffset = 0;
public static final double kBackLeftChassisAngularOffset = Math.PI;
public static final double kBackRightChassisAngularOffset = Math.PI / 2;
public static final double kFrontLeftChassisAngularOffset = Math.PI;
public static final double kFrontRightChassisAngularOffset = -Math.PI / 2;
public static final double kBackLeftChassisAngularOffset = Math.PI / 2;
public static final double kBackRightChassisAngularOffset = 0;
// 1, 7, 10 is the default for these three values
public static final double kSysIDDrivingRampRate = 1;
@@ -38,17 +38,17 @@ public class DrivetrainConstants {
public static final double kSysIDTurningTimeout = 10;
// SPARK MAX CAN IDs
public static final int kFrontLeftDrivingCanId = 11;
public static final int kRearLeftDrivingCanId = 13;
public static final int kFrontRightDrivingCanId = 15;
public static final int kRearRightDrivingCanId = 17;
public static final int kFrontLeftDrivingCanId = 0;
public static final int kRearLeftDrivingCanId = 2;
public static final int kFrontRightDrivingCanId = 1;
public static final int kRearRightDrivingCanId = 3;
public static final int kFrontLeftTurningCanId = 10;
public static final int kRearLeftTurningCanId = 12;
public static final int kFrontRightTurningCanId = 14;
public static final int kRearRightTurningCanId = 16;
public static final int kFrontLeftTurningCanId = 2;
public static final int kRearLeftTurningCanId = 4;
public static final int kFrontRightTurningCanId = 7;
public static final int kRearRightTurningCanId = 5;
public static final boolean kGyroReversed = false;
public static final boolean kGyroReversed = true;
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIGURATION ITEM

View File

@@ -11,31 +11,73 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
public class ElevatorConstants {
public static final int kElevatorMotor1ID = 0;
public static final int kElevatorMotor2ID = 0;
public enum ElevatorControlMode {
kPID,
kManualMaintain
}
public enum ElevatorPositions {
kStartingPosition(0),
kCoralIntake(0),
kL1(0),
kL2(14.5),
kL2Algae(22),
kL3(29),
kL3Algae(39),
kL4(53),
kL4Transition(40),
kProcessor(4);
private double position;
private ElevatorPositions(double position) {
this.position = position;
}
public double getPosition() {
return position;
}
}
public static final int kElevatorMotor1ID = 8;
public static final int kElevatorMotor2ID = 6;
public static final int kTopLimitSwitchID = 0;
public static final int kBottomLimitSwitchID = 0;
public static final double kEncoderConversionFactor = 0;
// 60/11 gearing multiplied by circumference of sprocket multiplied by 2 for carriage position
public static final double kEncoderPositionConversionFactor = 11.0/60.0 * (22.0*0.25) * 2.0;
public static final double kEncoderVelocityConversionFactor = kEncoderPositionConversionFactor / 60;
public static final int kMotorAmpsMax = 0;
public static final int kCurrentLimit = 40;
public static final double kPositionControllerP = 0;
public static final double kPositionControllerI = 0;
public static final double kPositionControllerD = 0;
public static final double kVelocityControllerP = 0;
public static final double kVelocityControllerI = 0;
public static final double kVelocityControllerD = 0;
public static final double kUpControllerP = 5.6;//7; //
public static final double kUpControllerI = 0;
public static final double kUpControllerD = 0.28;//0.28
public static final double kFeedForwardS = 0;
public static final double kFeedForwardG = 0;
public static final double kFeedForwardV = 0;
public static final double kDownControllerP = 5.6;//7; //
public static final double kDownControllerI = 0;
public static final double kDownControllerD = 0.57;//0.175;//0.1;//0.35
public static final double kAllowedError = 1;
public static final double kFeedForwardS = (0.95 - 0.2)/2*0.8; /* kG too high - kG too low / 2 0.95, 0.2 */
public static final double kFeedForwardG = (0.95 + 0.2)/2; /* kG too high + kG too low / 2 */ // calculated value 0.6
public static final double kFeedForwardV = 0.12; // calculated value 0.12
public static final double kFeedForwardAlgaeHeldS = 0;
public static final double kFeedForwardAlgaeHeldG = 0;
public static final double kFeedForwardAlgaeHeldV = 0;
public static final double kMaxVelocity = 150.0; // 120 inches per second (COOKING) calculated max is 184 in/s
public static final double kMaxAcceleration = 240; // 400 inches per second^2 (also COOKING) calculated max is 600 in/s^2
/**The position of the top of the elevator brace */
public static final double kBracePosition = 0;
public static final double kMaxHeight = 47.5; //actual is 53
// 1, 7, 10 are the defaults for these, change as necessary
public static final double kSysIDRampRate = 1;
public static final double kSysIDStepVolts = 7;
public static final double kSysIDRampRate = .25;
public static final double kSysIDStepVolts = 3;
public static final double kSysIDTimeout = 10;
public static final IdleMode kIdleMode = IdleMode.kBrake;
@@ -52,10 +94,11 @@ public class ElevatorConstants {
static {
motorConfig
.smartCurrentLimit(kMotorAmpsMax)
.idleMode(kIdleMode);
.smartCurrentLimit(kCurrentLimit)
.idleMode(kIdleMode)
.inverted(true);
motorConfig.encoder
.positionConversionFactor(kEncoderConversionFactor)
.velocityConversionFactor(kEncoderConversionFactor / 60.0);
.positionConversionFactor(kEncoderPositionConversionFactor)
.velocityConversionFactor(kEncoderVelocityConversionFactor);
}
}

View File

@@ -1,6 +0,0 @@
package frc.robot.constants;
public class IndexerConstants {
public static final int kIndexerMotorID = 0;
public static final int kIndexerBeamBreakID = 0;
}

View File

@@ -1,7 +1,12 @@
package frc.robot.constants;
import com.revrobotics.spark.config.SparkMaxConfig;
public class ManipulatorConstants {
public static final int kManipulatorMotorID = 0;
public static final int kCoralBeamBreakID = 0;
public static final int kAlgaeBeamBreakID = 0;
public static final int kManipulatorMotorID = 12;
public static final int kCoralBeamBreakID = 2;
public static final int kAlgaePhotoswitchID = 3;
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
}

View File

@@ -0,0 +1,81 @@
package frc.robot.constants;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
public class ManipulatorPivotConstants {
public static final int kPivotMotorID = 1;
public static final int kMotorCurrentMax = 40;
public static final double kPivotConversion = 2 * Math.PI;
public static final double kPivotMaxVelocity = 2 * Math.PI;
public static final double kPositionalP = 4;
public static final double kPositionalI = 0;
public static final double kPositionalD = 0;
public static final double kPositionalTolerance = Units.degreesToRadians(3.0);
public static final double kFeedForwardS = (0.3-0.19) / 2 * 0.8; //upper: 0.3 lower: 0.19
public static final double kFeedForwardG = (0.3+0.19) / 2; // calculated value 0.41
public static final double kFeedForwardV = 0.68; //calculated value 0.68
public static final double kFFGravityOffset = Units.degreesToRadians(135.0);
public static final double kMaxAcceleration = Units.degreesToRadians(1000.0); // degrees per second^2 calculated max = 2100
public static final double kMaxVelocity = Units.degreesToRadians(100.0); // degrees per second calculated max = 168
public static final double kEncoderOffset = 0.7815;
public static final double kCoralIntakePosition = Units.degreesToRadians(175.0);
public static final double kL1Position = Units.degreesToRadians(0.0);
public static final double kL2Position = Units.degreesToRadians(60.0);
public static final double kL3Position = Units.degreesToRadians(60.0);
public static final double kL4Position = Units.degreesToRadians(45.0);
public static final double kL2AlgaePosition = Units.degreesToRadians(175.0);
public static final double kL3AlgaePosition = Units.degreesToRadians(175.0);
public static final double kProcesserPosition = Units.degreesToRadians(175.0);
public static final double kNetPosition = Units.degreesToRadians(175.0);
/**The closest position to the elevator brace without hitting it */
public static final double kPivotSafeStowPosition = Units.degreesToRadians(67.0);
/**The forward rotation limit of the pivot */
public static final double kRotationLimit = Units.degreesToRadians(175.0);
public static final double kSysIDRampRate = 1;
public static final double kSysIDStepVolts = 7;
public static final double kSysIDTimeout = 10;
public static final IdleMode kIdleMode = IdleMode.kBrake;
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIG
public static final SysIdRoutine.Config kSysIDConfig = new Config(
Volts.of(kSysIDRampRate).per(Second),
Volts.of(kSysIDStepVolts),
Seconds.of(kSysIDTimeout)
);
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
static {
motorConfig
.smartCurrentLimit(kMotorCurrentMax)
.idleMode(kIdleMode)
.inverted(true);
motorConfig.absoluteEncoder
.positionConversionFactor(kPivotConversion)
.inverted(false)
.zeroOffset(kEncoderOffset);
}
}

View File

@@ -2,6 +2,12 @@ package frc.robot.constants;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.FeedbackConfigs;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.revrobotics.spark.config.SparkMaxConfig;
public class ModuleConstants {
@@ -20,52 +26,76 @@ public class ModuleConstants {
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction;
public static final int kDriveMotorCurrentLimit = 40;
public static final double kDrivingFactor = kWheelDiameterMeters * Math.PI / kDrivingMotorReduction;
public static final double kTurningFactor = 2 * Math.PI;
public static final double kDrivingVelocityFeedForward = 1 / kDriveWheelFreeSpeedRps;
public static final double kDriveP = .04;
public static final double kDriveI = 0;
public static final double kDriveD = 0;
public static final double kDriveS = 0;
public static final double kDriveV = kDrivingVelocityFeedForward;
public static final double kDriveA = 0;
public static final double kTurnP = 1;
public static final double kTurnI = 0;
public static final double kTurnD = 0;
public static final int kDriveMotorStatorCurrentLimit = 100;
public static final int kDriveMotorSupplyCurrentLimit = 65;
public static final int kTurnMotorCurrentLimit = 20;
public static final IdleMode kTurnIdleMode = IdleMode.kBrake;
public static final InvertedValue kDriveInversionState = InvertedValue.Clockwise_Positive;
public static final NeutralModeValue kDriveIdleMode = NeutralModeValue.Brake;
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIGURATION ITEM
public static final SparkMaxConfig drivingConfig = new SparkMaxConfig();
public static final SparkMaxConfig turningConfig = new SparkMaxConfig();
static {
// Use module constants to calculate conversion factors and feed forward gain.
double drivingFactor = kWheelDiameterMeters * Math.PI / kDrivingMotorReduction;
double turningFactor = 2 * Math.PI;
double drivingVelocityFeedForward = 1 / kDriveWheelFreeSpeedRps;
public static final FeedbackConfigs kDriveFeedConfig = new FeedbackConfigs();
public static final CurrentLimitsConfigs kDriveCurrentLimitConfig = new CurrentLimitsConfigs();
public static final MotorOutputConfigs kDriveMotorConfig = new MotorOutputConfigs();
public static final Slot0Configs kDriveSlot0Config = new Slot0Configs();
drivingConfig
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(kDriveMotorCurrentLimit);
drivingConfig.encoder
.positionConversionFactor(drivingFactor) // meters
.velocityConversionFactor(drivingFactor / 60.0); // meters per second
drivingConfig.closedLoop
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
// These are example gains you may need to them for your own robot!
.pid(0.04, 0, 0)
.velocityFF(drivingVelocityFeedForward)
.outputRange(-1, 1);
static {
kDriveFeedConfig.SensorToMechanismRatio = kDrivingMotorReduction;
kDriveCurrentLimitConfig.StatorCurrentLimitEnable = true;
kDriveCurrentLimitConfig.SupplyCurrentLimitEnable = true;
kDriveCurrentLimitConfig.StatorCurrentLimit = kDriveMotorStatorCurrentLimit;
kDriveCurrentLimitConfig.SupplyCurrentLimit = kDriveMotorSupplyCurrentLimit;
kDriveMotorConfig.Inverted = kDriveInversionState;
kDriveMotorConfig.NeutralMode = kDriveIdleMode;
kDriveSlot0Config.kP = kDriveP;
kDriveSlot0Config.kI = kDriveI;
kDriveSlot0Config.kD = kDriveD;
kDriveSlot0Config.kS = kDriveS;
kDriveSlot0Config.kV = kDriveV;
kDriveSlot0Config.kA = kDriveA;
turningConfig
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(20);
.idleMode(kTurnIdleMode)
.smartCurrentLimit(kTurnMotorCurrentLimit);
turningConfig.absoluteEncoder
// Invert the turning encoder, since the output shaft rotates in the opposite
// direction of the steering motor in the MAXSwerve Module.
.inverted(true)
.positionConversionFactor(turningFactor) // radians
.velocityConversionFactor(turningFactor / 60.0); // radians per second
.positionConversionFactor(kTurningFactor) // radians
.velocityConversionFactor(kTurningFactor / 60.0); // radians per second
turningConfig.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
// These are example gains you may need to them for your own robot!
.pid(1, 0, 0)
.pid(kTurnP, kTurnI, kTurnD)
.outputRange(-1, 1)
// Enable PID wrap around for the turning motor. This will allow the PID
// controller to go through 0 to get to the setpoint i.e. going from 350 degrees
// to 10 degrees will go through 0 rather than the other direction which is a
// longer route.
.positionWrappingEnabled(true)
.positionWrappingInputRange(0, turningFactor);
.positionWrappingInputRange(0, kTurningFactor);
}
}

View File

@@ -5,4 +5,7 @@ public class OIConstants {
public static final int kOperatorControllerPort = 1;
public static final double kDriveDeadband = 0.05;
public static final String kAutoTab = "Auto Tab";
public static final String kSensorsTab = "Sensors Tab";
}

View File

@@ -0,0 +1,31 @@
package frc.robot.constants;
public class VisionConstants {
// global coordinate map of all tags. index is the tag id.
// Units: inches and degrees. {x, y, z, z-rotation, y-rotation}
// This is for ANDYMARK FIELDS found in NE. Not for WELDED FIELDS.
public static final double[][] globalTagCoords = {{},
{656.98, 24.73, 58.50, 126.0, 0},
{656.98, 291.90, 58.50, 234.0, 0},
{452.4, 316.21, 51.25, 270, 0},
{365.2, 241.44, 73.54, 0, 30},
{365.2, 75.19, 73.54, 0, 30},
{530.49, 129.97, 12.13, 300, 0},
{546.87, 158.3, 12.13, 0, 0},
{530.49, 186.63, 12.13, 60, 0},
{497.77, 186.63, 12.13, 120, 0},
{481.39, 158.3, 12.13, 180, 0},
{497.77, 129.97, 12.13, 240, 0},
{33.9, 24.73, 58.5, 54, 0},
{33.9, 291.9, 58.5, 306, 0},
{325.68, 241.44, 73.54, 180, 30},
{325.68, 75.19, 73.54, 180, 30},
{238.49, 0.42, 51.25, 90, 0},
{160.39, 129.97, 12.13, 240, 0},
{144.00, 158.3, 12.13, 180, 0},
{160.39, 186.63, 12.13, 120, 0},
{193.1, 186.63, 12.13, 60, 0},
{209.49, 158.3, 12.13, 0, 0},
{193.1, 129.97, 12.13, 300, 0},
};
}

View File

@@ -1,68 +0,0 @@
package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import com.ctre.phoenix6.hardware.CANcoder;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ArmConstants;
public class Arm extends SubsystemBase {
private SparkMax armMotor;
private CANcoder canCoder;
private PIDController positionController;
private PIDController velocityController;
private ArmFeedforward feedForward;
public Arm() {
armMotor = new SparkMax(
ArmConstants.kArmMotorID,
MotorType.kBrushless
);
canCoder = new CANcoder(ArmConstants.kCANcoderID);
}
//manual command that keeps ouput speed consistent no matter the direction
public Command runArm(DoubleSupplier speed) {
return run(() -> {
double realSpeedTarget = speed.getAsDouble() * ArmConstants.kArmMaxVelocity;
double voltsOut = velocityController.calculate(
rotationsToRadians(canCoder.getVelocity().getValueAsDouble()),
realSpeedTarget
) + feedForward.calculate(
rotationsToRadians(canCoder.getPosition().getValueAsDouble()),
canCoder.getVelocity().getValueAsDouble()
);
armMotor.setVoltage(voltsOut);
});
}
public Command goToSetpoint(double setpoint, double timeout) {
return run(() -> {
double voltsOut = positionController.calculate(
canCoder.getPosition().getValueAsDouble(),
setpoint
) + feedForward.calculate(
canCoder.getPosition().getValueAsDouble(),
canCoder.getVelocity().getValueAsDouble()
);
armMotor.setVoltage(voltsOut);
}).until(positionController::atSetpoint).withTimeout(timeout);
}
protected double rotationsToRadians(double rotations) {
return rotations * 2 * Math.PI;
}
}

View File

@@ -2,10 +2,10 @@ package frc.robot.subsystems;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ClimberPivotConstants;
@@ -15,25 +15,19 @@ public class ClimberPivot extends SubsystemBase {
private RelativeEncoder neoEncoder;
private DigitalInput cageLimitSwitch;
private PIDController pidController;
public ClimberPivot() {
pivotMotor = new SparkMax(
ClimberPivotConstants.kPivotMotorID,
MotorType.kBrushless
);
neoEncoder = pivotMotor.getEncoder();
cageLimitSwitch = new DigitalInput(ClimberPivotConstants.kClimberLimitSwitchID);
pidController = new PIDController(
ClimberPivotConstants.kPIDControllerP,
ClimberPivotConstants.kPIDControllerI,
ClimberPivotConstants.kPIDControllerD
pivotMotor.configure(
ClimberPivotConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
neoEncoder = pivotMotor.getEncoder();
}
public Command runPivot(double speed) {
@@ -42,18 +36,20 @@ public class ClimberPivot extends SubsystemBase {
});
}
public Command goToAngle(double setpoint, double timeout) {
/**
* Runs the climber until it is at setpoint
*
* @param speed The speed at which the pivot runs
* @param setpoint The target position of the climber
* @return Sets the motor speed until at the target position
*/
public Command climb(double setpoint, double speed) {
return run(() -> {
pivotMotor.set(
pidController.calculate(
neoEncoder.getPosition(),
setpoint
)
);
}).withTimeout(timeout);
pivotMotor.set(speed);
}).until(() -> neoEncoder.getPosition() >= setpoint);
}
public boolean getCageLimitSwitch() {
return cageLimitSwitch.get();
public double getEncoderPosition() {
return neoEncoder.getPosition();
}
}
}

View File

@@ -1,12 +1,15 @@
package frc.robot.subsystems;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ClimberRollersConstants;
//TODO Figure out a way to detect if we're at the top of the cage
public class ClimberRollers extends SubsystemBase {
private SparkMax rollerMotor;
@@ -15,8 +18,20 @@ public class ClimberRollers extends SubsystemBase {
ClimberRollersConstants.kRollerMotorID,
MotorType.kBrushless
);
rollerMotor.configure(
ClimberRollersConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
}
/**
* Runs the rollers at a set speed
*
* @param speed The speed in which the roller runs
* @return Runs the rollers at a set speed
*/
public Command runRoller(double speed) {
return run(() -> {
rollerMotor.set(speed);

View File

@@ -4,21 +4,27 @@
package frc.robot.subsystems;
import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import com.pathplanner.lib.auto.AutoBuilder;
import com.studica.frc.AHRS;
import com.studica.frc.AHRS.NavXComType;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.ADIS16470_IMU;
import edu.wpi.first.wpilibj.ADIS16470_IMU.IMUAxis;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.AutoConstants;
import frc.robot.constants.DrivetrainConstants;
import frc.robot.constants.OIConstants;
@@ -30,10 +36,12 @@ public class Drivetrain extends SubsystemBase {
protected MAXSwerveModule m_rearRight;
// The gyro sensor
private ADIS16470_IMU m_gyro;
private AHRS gyro;
// Odometry class for tracking robot pose
private SwerveDriveOdometry m_odometry;
private SwerveDrivePoseEstimator m_estimator;
private Vision vision;
/** Creates a new DriveSubsystem. */
public Drivetrain() {
@@ -61,30 +69,85 @@ public class Drivetrain extends SubsystemBase {
DrivetrainConstants.kBackRightChassisAngularOffset
);
m_gyro = new ADIS16470_IMU();
gyro = new AHRS(NavXComType.kMXP_SPI);
m_odometry = new SwerveDriveOdometry(
m_estimator = new SwerveDrivePoseEstimator(
DrivetrainConstants.kDriveKinematics,
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
Rotation2d.fromDegrees(gyro.getAngle()),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
});
},
new Pose2d()
);
AutoBuilder.configure(
this::getPose,
this::resetOdometry,
this::getCurrentChassisSpeeds,
this::driveWithChassisSpeeds,
AutoConstants.kPPDriveController,
AutoConstants.kRobotConfig,
() -> {
Optional<DriverStation.Alliance> alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
},
this
);
}
@Override
public void periodic() {
// Update the odometry in the periodic block
m_odometry.update(
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
m_estimator.update(
Rotation2d.fromDegrees(getGyroValue()),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
});
// if the detected tags match your alliances reef tags use their pose estimates
/*
if(vision.getOrangeClosestTag() >= 6 || vision.getOrangeClosestTag() <= 11 || DriverStation.getAlliance().equals(Alliance.Red)){
m_estimator.addVisionMeasurement(vision.getOrangeGlobalPose(), vision.getOrangeTimeStamp());
}else if(vision.getOrangeClosestTag() >= 17 || vision.getOrangeClosestTag() <= 22 || DriverStation.getAlliance().equals(Alliance.Blue)){
m_estimator.addVisionMeasurement(vision.getOrangeGlobalPose(), vision.getOrangeTimeStamp());
}
if(vision.getBlackClosestTag() >= 6 || vision.getBlackClosestTag() <= 11 || DriverStation.getAlliance().equals(Alliance.Red)){
m_estimator.addVisionMeasurement(vision.getBlackGlobalPose(), vision.getBlackTimeStamp());
}else if(vision.getBlackClosestTag() >= 17 || vision.getBlackClosestTag() <= 22 || DriverStation.getAlliance().equals(Alliance.Blue)){
m_estimator.addVisionMeasurement(vision.getBlackGlobalPose(), vision.getBlackTimeStamp());
}
*/
}
public ChassisSpeeds getCurrentChassisSpeeds() {
return DrivetrainConstants.kDriveKinematics.toChassisSpeeds(
m_frontLeft.getState(),
m_frontRight.getState(),
m_rearLeft.getState(),
m_rearRight.getState()
);
}
public void driveWithChassisSpeeds(ChassisSpeeds speeds) {
ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.2);
SwerveModuleState[] newStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(discreteSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(newStates, DrivetrainConstants.kMaxSpeedMetersPerSecond);
setModuleStates(newStates);
}
/**
@@ -93,7 +156,7 @@ public class Drivetrain extends SubsystemBase {
* @return The pose.
*/
public Pose2d getPose() {
return m_odometry.getPoseMeters();
return m_estimator.getEstimatedPosition();
}
/**
@@ -102,14 +165,7 @@ public class Drivetrain extends SubsystemBase {
* @param pose The pose to which to set the odometry.
*/
public void resetOdometry(Pose2d pose) {
m_odometry.resetPosition(
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
},
m_estimator.resetPose(
pose
);
}
@@ -144,7 +200,7 @@ public class Drivetrain extends SubsystemBase {
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered,
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)))
Rotation2d.fromDegrees(getGyroValue()))
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
SwerveDriveKinematics.desaturateWheelSpeeds(
swerveModuleStates, DrivetrainConstants.kMaxSpeedMetersPerSecond);
@@ -194,7 +250,11 @@ public class Drivetrain extends SubsystemBase {
/** Zeroes the heading of the robot. */
public void zeroHeading() {
m_gyro.reset();
gyro.reset();
}
public double getGyroValue() {
return gyro.getAngle() * (DrivetrainConstants.kGyroReversed ? -1 : 1);
}
/**
@@ -203,7 +263,7 @@ public class Drivetrain extends SubsystemBase {
* @return the robot's heading in degrees, from -180 to 180
*/
public double getHeading() {
return Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)).getDegrees();
return Rotation2d.fromDegrees(getGyroValue()).getDegrees();
}
/**
@@ -212,6 +272,10 @@ public class Drivetrain extends SubsystemBase {
* @return The turn rate of the robot, in degrees per second
*/
public double getTurnRate() {
return m_gyro.getRate(IMUAxis.kZ) * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0);
return gyro.getRate() * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0);
}
public void addVisionMeasurement(Pose2d pose, double timestamp){
m_estimator.addVisionMeasurement(pose, timestamp);
}
}

View File

@@ -1,21 +1,23 @@
package frc.robot.subsystems;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ElevatorFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ElevatorConstants;
import frc.robot.constants.ElevatorConstants.ElevatorControlMode;
import frc.robot.constants.ElevatorConstants.ElevatorPositions;
public class Elevator extends SubsystemBase {
protected SparkMax elevatorMotor1;
@@ -23,15 +25,20 @@ public class Elevator extends SubsystemBase {
protected RelativeEncoder encoder;
private DigitalInput topLimitSwitch;
private BooleanSupplier hasAlgae;
private DigitalInput bottomLimitSwitch;
private PIDController positionController;
private PIDController velocityController;
private PIDController pidController;
private ElevatorFeedforward feedForward;
private ElevatorFeedforward algaeHeldFeedForward;
private ElevatorControlMode mode;
private ElevatorPositions currentTargetPosition;
public Elevator() {
public Elevator(BooleanSupplier hasAlgae) {
elevatorMotor1 = new SparkMax(
ElevatorConstants.kElevatorMotor1ID,
MotorType.kBrushless
@@ -56,59 +63,175 @@ public class Elevator extends SubsystemBase {
encoder = elevatorMotor1.getEncoder();
topLimitSwitch = new DigitalInput(
ElevatorConstants.kTopLimitSwitchID
);
this.hasAlgae = hasAlgae;
bottomLimitSwitch = new DigitalInput(
ElevatorConstants.kBottomLimitSwitchID
);
positionController = new PIDController(
ElevatorConstants.kPositionControllerP,
ElevatorConstants.kPositionControllerI,
ElevatorConstants.kPositionControllerD
pidController = new PIDController(
ElevatorConstants.kDownControllerP,
ElevatorConstants.kDownControllerI,
ElevatorConstants.kDownControllerD
);
pidController.setSetpoint(0);
velocityController = new PIDController(
ElevatorConstants.kVelocityControllerP,
ElevatorConstants.kVelocityControllerI,
ElevatorConstants.kVelocityControllerD
);
pidController.setTolerance(ElevatorConstants.kAllowedError);
feedForward = new ElevatorFeedforward(
ElevatorConstants.kFeedForwardS,
ElevatorConstants.kFeedForwardG,
ElevatorConstants.kFeedForwardV
);
algaeHeldFeedForward = new ElevatorFeedforward(
ElevatorConstants.kFeedForwardAlgaeHeldS,
ElevatorConstants.kFeedForwardAlgaeHeldG,
ElevatorConstants.kFeedForwardAlgaeHeldV
);
mode = ElevatorControlMode.kPID;
currentTargetPosition = ElevatorPositions.kCoralIntake;
}
//manual command that keeps ouput speed consistent no matter the direction
public Command runElevator(DoubleSupplier speed) {
return run(() -> {
double realSpeedTarget = speed.getAsDouble() * ElevatorConstants.kElevatorMaxVelocity;
@Override
public void periodic() {
if (!getBottomLimitSwitch()) {
encoder.setPosition(0);
}
double voltsOut = velocityController.calculate(
encoder.getVelocity(),
realSpeedTarget
) + feedForward.calculate(realSpeedTarget);
elevatorMotor1.setVoltage(voltsOut);
}).until(() -> topLimitSwitch.get() || bottomLimitSwitch.get());
if(mode == ElevatorControlMode.kPID) {
if (!pidController.atSetpoint()) {
elevatorMotor1.setVoltage(
pidController.calculate(
encoder.getPosition(),
currentTargetPosition.getPosition()
) + (hasAlgae.getAsBoolean() ? algaeHeldFeedForward.calculate(0) : feedForward.calculate(0))
);
} else {
if (hasAlgae.getAsBoolean()) {
elevatorMotor1.setVoltage(
algaeHeldFeedForward.calculate(0)
);
} else {
elevatorMotor1.setVoltage(
feedForward.calculate(0)
);
}
}
}
}
/**
* Returns whether or not the motion is safe relative to the encoder's current position
* and the elevator brace position
*
* @return Is the motion safe
*/
public boolean isMotionSafe() {
return isMotionSafe(getEncoderPosition());
}
/**
* Returns whether or not the motion is safe relative to some target position and the elevator
* brace position
*
* @param motionTarget The target position to determine the safety of
* @return Is the motion safe
*/
public boolean isMotionSafe(double motionTarget) {
return motionTarget > ElevatorConstants.kBracePosition;
}
//go to setpoint command
public Command goToSetpoint(double setpoint, double timeout) {
return run(() -> {
double voltsOut = positionController.calculate(
encoder.getPosition(),
setpoint
) + feedForward.calculate(0);
/**
* A manual translation command that uses feed forward calculation to maintain position
*
* @param speed The speed at which the elevator translates
* @return Sets motor voltage to translate the elevator and maintain position
*/
public Command runManualElevator(DoubleSupplier speed) {
return startRun(() -> {
mode = ElevatorControlMode.kManualMaintain;
},
() -> {
double desired = speed.getAsDouble();
elevatorMotor1.setVoltage(voltsOut);
}).until(
() -> positionController.atSetpoint() || topLimitSwitch.get() || bottomLimitSwitch.get()
).withTimeout(timeout);
if(Math.abs(MathUtil.applyDeadband(desired, .05)) > 0) {
elevatorMotor1.set(
speed.getAsDouble()
);
} else {
if (hasAlgae.getAsBoolean()) {
elevatorMotor1.setVoltage(
algaeHeldFeedForward.calculate(0)
);
} else {
elevatorMotor1.setVoltage(
feedForward.calculate(0)
);
}
}
});
}
}
public Command setTargetPosition(ElevatorPositions position) {
return runOnce(() -> {
if (mode == ElevatorControlMode.kManualMaintain) {
pidController.reset();
mode = ElevatorControlMode.kPID;
}
currentTargetPosition = position;
});
}
public boolean atSetpoint() {
return pidController.atSetpoint();
}
/**
* Returns the current encoder position
*
* @return Current encoder position
*/
public double getEncoderPosition() {
return encoder.getPosition();
}
/**
* Returns the value of the bottom limit switch on the elevator (false = disabled, true = enabled)
*
* @return The value of bottomLimitSwitch
*/
public boolean getBottomLimitSwitch() {
return bottomLimitSwitch.get();
}
/**
* Returns the motor's output current
*
* @return Motor output current
*/
public double getMotor1() {
return elevatorMotor1.getAppliedOutput()*elevatorMotor1.getBusVoltage();
}
/**
* Returns the motor's output current
*
* @return Motor output current
*/
public double getMotor2() {
return elevatorMotor2.getAppliedOutput()*elevatorMotor2.getBusVoltage();
}
public double getPIDSetpoint() {
return pidController.getSetpoint();
}
public double getPIDError() {
return pidController.getError();
}
}

View File

@@ -1,36 +0,0 @@
package frc.robot.subsystems;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.IndexerConstants;
public class Indexer extends SubsystemBase {
private SparkMax indexerMotor;
private DigitalInput indexerBeamBreak;
public Indexer() {
indexerMotor = new SparkMax(
IndexerConstants.kIndexerMotorID,
MotorType.kBrushless
);
indexerBeamBreak = new DigitalInput(IndexerConstants.kIndexerBeamBreakID);
}
public Command runIndexer(double speed) {
return run(() -> {
indexerMotor.set(speed);
});
}
public Command indexCoral(double speed) {
return run(() -> {
indexerMotor.set(speed);
}).until(indexerBeamBreak::get);
}
}

View File

@@ -15,117 +15,127 @@ import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.RelativeEncoder;
import frc.robot.constants.ModuleConstants;
public class MAXSwerveModule {
private final SparkMax m_drivingSpark;
private final SparkMax m_turningSpark;
private final TalonFX m_drive;
private final SparkMax m_turningSpark;
private final RelativeEncoder m_drivingEncoder;
private final AbsoluteEncoder m_turningEncoder;
private final AbsoluteEncoder m_turningEncoder;
private final SparkClosedLoopController m_drivingClosedLoopController;
private final SparkClosedLoopController m_turningClosedLoopController;
private final SparkClosedLoopController m_turningClosedLoopController;
private double m_chassisAngularOffset = 0;
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());
private final VelocityVoltage driveVelocityRequest;
/**
* Constructs a MAXSwerveModule and configures the driving and turning motor,
* encoder, and PID controller. This configuration is specific to the REV
* MAXSwerve Module built with NEOs, SPARKS MAX, and a Through Bore
* Encoder.
*/
public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngularOffset) {
m_drivingSpark = new SparkMax(drivingCANId, MotorType.kBrushless);
m_turningSpark = new SparkMax(turningCANId, MotorType.kBrushless);
private double m_chassisAngularOffset = 0;
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());
m_drivingEncoder = m_drivingSpark.getEncoder();
m_turningEncoder = m_turningSpark.getAbsoluteEncoder();
/**
* Constructs a MAXSwerveModule and configures the driving and turning motor,
* encoder, and PID controller. This configuration is specific to the REV
* MAXSwerve Module built with NEOs, SPARKS MAX, and a Through Bore
* Encoder.
*/
public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngularOffset) {
m_drive = new TalonFX(drivingCANId);
m_turningSpark = new SparkMax(turningCANId, MotorType.kBrushless);
m_drivingClosedLoopController = m_drivingSpark.getClosedLoopController();
m_turningClosedLoopController = m_turningSpark.getClosedLoopController();
m_turningEncoder = m_turningSpark.getAbsoluteEncoder();
// Apply the respective configurations to the SPARKS. Reset parameters before
// applying the configuration to bring the SPARK to a known good state. Persist
// the settings to the SPARK to avoid losing them on a power cycle.
m_drivingSpark.configure(ModuleConstants.drivingConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);
m_turningSpark.configure(ModuleConstants.turningConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);
m_turningClosedLoopController = m_turningSpark.getClosedLoopController();
m_chassisAngularOffset = chassisAngularOffset;
m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
m_drivingEncoder.setPosition(0);
}
driveVelocityRequest = new VelocityVoltage(0).withSlot(0);
/**
* Returns the current state of the module.
*
* @return The current state of the module.
*/
public SwerveModuleState getState() {
// Apply chassis angular offset to the encoder position to get the position
// relative to the chassis.
return new SwerveModuleState(m_drivingEncoder.getVelocity(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
}
// Apply the respective configurations to the SPARKS. Reset parameters before
// applying the configuration to bring the SPARK to a known good state. Persist
// the settings to the SPARK to avoid losing them on a power cycle.
m_drive.getConfigurator().apply(ModuleConstants.kDriveCurrentLimitConfig);
m_drive.getConfigurator().apply(ModuleConstants.kDriveFeedConfig);
m_drive.getConfigurator().apply(ModuleConstants.kDriveMotorConfig);
m_drive.getConfigurator().apply(ModuleConstants.kDriveSlot0Config);
/**
* Returns the current position of the module.
*
* @return The current position of the module.
*/
public SwerveModulePosition getPosition() {
// Apply chassis angular offset to the encoder position to get the position
// relative to the chassis.
return new SwerveModulePosition(
m_drivingEncoder.getPosition(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
}
m_turningSpark.configure(ModuleConstants.turningConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);
/**
* Sets the desired state for the module.
*
* @param desiredState Desired state with speed and angle.
*/
public void setDesiredState(SwerveModuleState desiredState) {
// Apply chassis angular offset to the desired state.
SwerveModuleState correctedDesiredState = new SwerveModuleState();
correctedDesiredState.speedMetersPerSecond = desiredState.speedMetersPerSecond;
correctedDesiredState.angle = desiredState.angle.plus(Rotation2d.fromRadians(m_chassisAngularOffset));
m_chassisAngularOffset = chassisAngularOffset;
m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
m_drive.setPosition(0);
}
// Optimize the reference state to avoid spinning further than 90 degrees.
correctedDesiredState.optimize(new Rotation2d(m_turningEncoder.getPosition()));
/**
* Returns the current state of the module.
*
* @return The current state of the module.
*/
public SwerveModuleState getState() {
// Apply chassis angular offset to the encoder position to get the position
// relative to the chassis.
return new SwerveModuleState(m_drive.getVelocity().getValueAsDouble(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
}
// Command driving and turning SPARKS towards their respective setpoints.
m_drivingClosedLoopController.setReference(correctedDesiredState.speedMetersPerSecond, ControlType.kVelocity);
m_turningClosedLoopController.setReference(correctedDesiredState.angle.getRadians(), ControlType.kPosition);
/**
* Returns the current position of the module.
*
* @return The current position of the module.
*/
public SwerveModulePosition getPosition() {
// Apply chassis angular offset to the encoder position to get the position
// relative to the chassis.
return new SwerveModulePosition(m_drive.getPosition().getValueAsDouble(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
}
m_desiredState = desiredState;
}
/**
* Sets the desired state for the module.
*
* @param desiredState Desired state with speed and angle.
*/
public void setDesiredState(SwerveModuleState desiredState) {
// Apply chassis angular offset to the desired state.
SwerveModuleState correctedDesiredState = new SwerveModuleState();
correctedDesiredState.speedMetersPerSecond = desiredState.speedMetersPerSecond;
correctedDesiredState.angle = desiredState.angle.plus(Rotation2d.fromRadians(m_chassisAngularOffset));
public void setVoltageDrive(double voltage){
m_drivingSpark.setVoltage(voltage);
}
// Optimize the reference state to avoid spinning further than 90 degrees.
correctedDesiredState.optimize(new Rotation2d(m_turningEncoder.getPosition()));
public void setVoltageTurn(double voltage) {
m_turningSpark.setVoltage(voltage);
}
// Command driving and turning SPARKS towards their respective setpoints.
m_drive.setControl(
driveVelocityRequest.withVelocity(
correctedDesiredState.speedMetersPerSecond
).withFeedForward(
correctedDesiredState.speedMetersPerSecond
)
);
public double getVoltageDrive() {
return m_drivingSpark.get() * RobotController.getBatteryVoltage();
}
m_turningClosedLoopController.setReference(correctedDesiredState.angle.getRadians(), ControlType.kPosition);
public double getVoltageTurn() {
return m_turningSpark.get() * RobotController.getBatteryVoltage();
}
m_desiredState = desiredState;
}
/** Zeroes all the SwerveModule encoders. */
public void resetEncoders() {
m_drivingEncoder.setPosition(0);
}
public void setVoltageDrive(double voltage){
m_drive.setVoltage(voltage);
}
public void setVoltageTurn(double voltage) {
m_turningSpark.setVoltage(voltage);
}
public double getVoltageDrive() {
return m_drive.get() * RobotController.getBatteryVoltage();
}
public double getVoltageTurn() {
return m_turningSpark.get() * RobotController.getBatteryVoltage();
}
/** Zeroes all the SwerveModule encoders. */
public void resetEncoders() {
m_drive.setPosition(0);
}
}

View File

@@ -1,6 +1,10 @@
package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
@@ -12,7 +16,7 @@ public class Manipulator extends SubsystemBase {
private SparkMax manipulatorMotor;
private DigitalInput coralBeamBreak;
private DigitalInput algaeBeamBreak;
private DigitalInput algaePhotoswitch;
public Manipulator() {
manipulatorMotor = new SparkMax(
@@ -20,25 +24,76 @@ public class Manipulator extends SubsystemBase {
MotorType.kBrushless
);
manipulatorMotor.configure(
ManipulatorConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
coralBeamBreak = new DigitalInput(ManipulatorConstants.kCoralBeamBreakID);
algaeBeamBreak = new DigitalInput(ManipulatorConstants.kAlgaeBeamBreakID);
algaePhotoswitch = new DigitalInput(ManipulatorConstants.kAlgaePhotoswitchID);
}
public Command runManipulator(double speed) {
/**
* The default command for the manipulator that either stops the manipulator or slowly
* runs the manipulator to retain the algae
*
* @return Returns a command that sets the speed of the motor
*/
public Command defaultCommand() {
return run(() -> {
manipulatorMotor.set(speed);
runUntilCollected(() -> 0.1);
});
}
/**
* Runs the manipulator at a set speed with the direction based on the coral parameter
*
* @param speed The speed at which the manipulator runs
* @param coral Is the manipulator manipulating a coral? (True = Coral, False = Algae)
* @return Returns a command that sets the speed of the motor
*/
public Command runManipulator(DoubleSupplier speed, boolean coral) {
return run(() -> {
manipulatorMotor.set(
coral ? speed.getAsDouble() : speed.getAsDouble() * -1
);
});
}
public Command runUntilCollected(double speed, boolean coral) {
/**
* Runs the manipulator until either the algae or coral beam break reads true
*
* @param speed The speed at which the manipulator is run
* @param coral Is the object a coral? (True = Coral, False = Algae)
* @return Returns a command that sets the speed of the motor
*/
public Command runUntilCollected(DoubleSupplier speed) {
return run(() -> {
manipulatorMotor.set(coral ? speed : speed * -1);
}).until(() -> coralBeamBreak.get() || algaeBeamBreak.get());
manipulatorMotor.set(
speed.getAsDouble()
);
}).until(() -> !coralBeamBreak.get());
}
public Command indexCoral(double speed) {
/**
* Runs the manipulator in a way that will bring the coral to a reliable holding position
*
* @return Returns a command that will position the coral to a known location
*/
public Command indexCoral() {
return run(() -> {
manipulatorMotor.set(speed);
}).until(coralBeamBreak::get);
runUntilCollected(() -> 0.5)
.andThen(runManipulator(() -> .1, false))
.until(() -> getCoralBeamBreak());
});
}
public boolean getCoralBeamBreak() {
return coralBeamBreak.get();
}
public boolean getAlgaePhotoswitch() {
return algaePhotoswitch.get();
}
}

View File

@@ -0,0 +1,183 @@
package frc.robot.subsystems;
import com.revrobotics.spark.SparkMax;
import java.util.function.DoubleSupplier;
import com.revrobotics.spark.SparkAbsoluteEncoder;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ManipulatorPivotConstants;
public class ManipulatorPivot extends SubsystemBase {
protected SparkMax pivotMotor;
private SparkAbsoluteEncoder encoder;
private ArmFeedforward feedForward;
private PIDController pidController;
public ManipulatorPivot() {
pivotMotor = new SparkMax(
ManipulatorPivotConstants.kPivotMotorID,
MotorType.kBrushless
);
pivotMotor.configure(
ManipulatorPivotConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
encoder = pivotMotor.getAbsoluteEncoder();
pidController = new PIDController(
ManipulatorPivotConstants.kPositionalP,
ManipulatorPivotConstants.kPositionalI,
ManipulatorPivotConstants.kPositionalD
);
pidController.setSetpoint(0);
pidController.disableContinuousInput();
feedForward = new ArmFeedforward(
ManipulatorPivotConstants.kFeedForwardS,
ManipulatorPivotConstants.kFeedForwardG,
ManipulatorPivotConstants.kFeedForwardV
);
}
/**
* Returns whether or not the motion is safe relative to the encoder's current position
* and the arm safe stow position
*
* @return Is the motion safe
*/
public boolean isMotionSafe() {
return isMotionSafe(getEncoderPosition());
}
/**
* Returns whether or not the motion is safe relative to some target position and the
* arm safe stow position
*
* @param motionTarget The target position to determine the safety of
* @return Is the motion safe
*/
public boolean isMotionSafe(double motionTarget) {
return motionTarget > ManipulatorPivotConstants.kPivotSafeStowPosition;
}
/**
* Manual ManipulatorPivot command that sets the motor based on speed
*
* @param speed The speed to set the motor
* @return A command that sets the motor speed
*/
public Command runManualPivot(DoubleSupplier speed) {
return run(() -> {
pivotMotor.set(speed.getAsDouble());
});
}
/**
* Moves the arm to a target destination (setpoint)
*
* @param setpoint Target destination of the subsystem
* @param timeout Time to achieve the setpoint before quitting
* @return Sets motor voltage to achieve the target destination
*/
public Command goToSetpoint(DoubleSupplier setpoint) {
return startRun(() -> {
pidController.setSetpoint(setpoint.getAsDouble());
pidController.reset();
},
() -> {
/*
if (!pidController.atSetpoint()) {
pivotMotor.setVoltage(
pidController.calculate(
encoder.getPosition(),
setpoint.getAsDouble()
) - feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
} else {
pivotMotor.setVoltage(
-feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
}
*/
pivotMotor.setVoltage(
pidController.calculate(
encoder.getPosition(),
setpoint.getAsDouble()
) - feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
}).until(() -> pidController.atSetpoint());
}
public Command maintainPosition() {
return startRun(() -> {
pidController.reset();
},
() -> {
/*
if (!pidController.atSetpoint()) {
pivotMotor.setVoltage(
pidController.calculate(
encoder.getPosition(),
setpoint.getAsDouble()
) - feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
} else {
pivotMotor.setVoltage(
-feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
}
*/
pivotMotor.setVoltage(
pidController.calculate(
encoder.getPosition(),
pidController.getSetpoint()
) - feedForward.calculate(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset, 0)
);
});
}
/**
* Returns the encoder's position in radians
*
* @return Encoder's position in radians
*/
public double getEncoderPosition() {
return Units.radiansToDegrees( encoder.getPosition());
}
/**
* Returns the encoder's velocity in radians per second
*
* @return Encoder's velocity in radians per second
*/
public double getEncoderVelocity() {
return Units.radiansToDegrees(encoder.getVelocity());
}
public double getCGPosition(){
return Units.radiansToDegrees(-encoder.getPosition() + ManipulatorPivotConstants.kFFGravityOffset);
}
public double getPivotOutput(){
return pivotMotor.getAppliedOutput() * pivotMotor.getBusVoltage();
}
}

View File

@@ -0,0 +1,144 @@
package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.networktables.BooleanSubscriber;
import edu.wpi.first.networktables.DoubleSubscriber;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import frc.robot.constants.VisionConstants;
public class Vision{
private DoubleSubscriber blackRobotRelativeX;
private DoubleSubscriber blackRobotRelativeY;
private DoubleSubscriber blackRobotRelativeZ;
private DoubleSubscriber blackClosestTag;
private BooleanSubscriber blackTagDetected;
private DoubleSubscriber blackFramerate;
private DoubleSubscriber orangeRobotRelativeX;
private DoubleSubscriber orangeRobotRelativeY;
private DoubleSubscriber orangeRobotRelativeZ;
private DoubleSubscriber orangeClosestTag;
private BooleanSubscriber orangeTagDetected;
private DoubleSubscriber orangeFramerate;
private DoubleSupplier gyroAngle;
public Vision(DoubleSupplier gyroAngle){
NetworkTableInstance inst = NetworkTableInstance.getDefault();
NetworkTable blackVisionTable = inst.getTable("black_Fiducial");
NetworkTable orangeVisionTable = inst.getTable("orange_Fiducial");
blackRobotRelativeX = orangeVisionTable.getDoubleTopic("blackRelativeX").subscribe(0.0);
blackRobotRelativeY = orangeVisionTable.getDoubleTopic("blackRelativeY").subscribe(0.0);
blackRobotRelativeZ = orangeVisionTable.getDoubleTopic("blackRelativeZ").subscribe(0.0);
blackClosestTag = blackVisionTable.getDoubleTopic("blackClosestTag").subscribe(0.0);
blackTagDetected = blackVisionTable.getBooleanTopic("blackTagDetected").subscribe(false);
blackFramerate = blackVisionTable.getDoubleTopic("blackFPS").subscribe(0.0);
orangeRobotRelativeX = orangeVisionTable.getDoubleTopic("orangeRelativeX").subscribe(0.0);
orangeRobotRelativeY = orangeVisionTable.getDoubleTopic("orangeRelativeY").subscribe(0.0);
orangeRobotRelativeZ = orangeVisionTable.getDoubleTopic("orangeRelativeZ").subscribe(0.0);
orangeClosestTag = orangeVisionTable.getDoubleTopic("orangeClosestTag").subscribe(0.0);
orangeTagDetected = orangeVisionTable.getBooleanTopic("orangeTagDetected").subscribe(false);
orangeFramerate = orangeVisionTable.getDoubleTopic("orangeFPS").subscribe(0.0);
}
public Pose2d relativeToGlobalPose2d(int tagID, Translation2d relativeCoords, Rotation2d gyroAngle){
Pose2d tag2dPose = new Pose2d(VisionConstants.globalTagCoords[tagID][0],
VisionConstants.globalTagCoords[tagID][1],
new Rotation2d());
Pose2d relative = new Pose2d(relativeCoords, gyroAngle);
Transform2d relative2dTransformation = new Transform2d(relative.getTranslation(), relative.getRotation());
Pose2d globalPose = tag2dPose.transformBy(relative2dTransformation.inverse());
return new Pose2d(globalPose.getTranslation(), gyroAngle);
}
public Pose2d getBlackGlobalPose(){
return relativeToGlobalPose2d(getBlackClosestTag(),
new Translation2d(getBlackRelativeX(), getBlackRelativeY()),
new Rotation2d(gyroAngle.getAsDouble()));
}
public double getBlackRelativeX(){
return blackRobotRelativeX.get();
}
public double getBlackRelativeY(){
return blackRobotRelativeY.get();
}
public double getBlackRelativeZ(){
return blackRobotRelativeZ.get();
}
public int getBlackClosestTag(){
return (int) blackClosestTag.get();
}
public double getBlackTimeStamp(){
return blackRobotRelativeX.getLastChange();
}
public boolean getBlackTagDetected(){
return blackTagDetected.get();
}
public double getBlackFPS(){
return blackFramerate.get();
}
public Pose2d getOrangeGlobalPose(){
return relativeToGlobalPose2d(getOrangeClosestTag(),
new Translation2d(getOrangeRelativeX(), getOrangeRelativeY()),
new Rotation2d(gyroAngle.getAsDouble()));
}
public double getOrangeRelativeX(){
return orangeRobotRelativeX.get();
}
public double getOrangeRelativeY(){
return orangeRobotRelativeY.get();
}
public double getOrangeRelativeZ(){
return orangeRobotRelativeZ.get();
}
public int getOrangeClosestTag(){
return (int) orangeClosestTag.get();
}
public double getOrangeTimeStamp(){
return orangeRobotRelativeX.getLastChange();
}
public boolean getOrangeTagDetected(){
return orangeTagDetected.get();
}
public double getOrangeFPS(){
return orangeFramerate.get();
}
}

View File

@@ -1,8 +1,11 @@
package frc.robot.subsystems.sysid;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.Inches;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.MetersPerSecond;
import java.util.function.BooleanSupplier;
import static edu.wpi.first.units.Units.InchesPerSecond;
import edu.wpi.first.units.measure.MutDistance;
import edu.wpi.first.units.measure.MutLinearVelocity;
@@ -22,14 +25,14 @@ public class ElevatorSysID extends Elevator {
private SysIdRoutine routine;
public ElevatorSysID() {
super();
public ElevatorSysID(BooleanSupplier hasAlgae) {
super(hasAlgae);
appliedVoltage = Volts.mutable(0);
elevatorPosition = Meters.mutable(0);
elevatorPosition = Inches.mutable(0);
elevatorVelocity = MetersPerSecond.mutable(0);
elevatorVelocity = InchesPerSecond.mutable(0);
routine = new SysIdRoutine(
ElevatorConstants.kSysIDConfig,
@@ -38,13 +41,13 @@ public class ElevatorSysID extends Elevator {
(log) -> {
log.motor("elevatorMotor1")
.voltage(appliedVoltage.mut_replace(
elevatorMotor1.get() * RobotController.getBatteryVoltage(), Volts
getMotor1(), Volts
))
.linearPosition(elevatorPosition.mut_replace(
encoder.getPosition(), Meters
encoder.getPosition(), Inches
))
.linearVelocity(elevatorVelocity.mut_replace(
encoder.getVelocity(), MetersPerSecond
encoder.getVelocity(), InchesPerSecond
));
},
this
@@ -52,6 +55,11 @@ public class ElevatorSysID extends Elevator {
);
}
@Override
public void periodic() {
}
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
return routine.quasistatic(direction);
}

View File

@@ -0,0 +1,62 @@
package frc.robot.subsystems.sysid;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.Radians;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import edu.wpi.first.units.measure.MutAngle;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.constants.ManipulatorPivotConstants;
import frc.robot.subsystems.ManipulatorPivot;
public class ManipulatorPivotSysID extends ManipulatorPivot {
private MutVoltage appliedVoltage;
private MutAngle pivotPosition;
private MutAngularVelocity pivotVelocity;
private SysIdRoutine routine;
public ManipulatorPivotSysID() {
super();
appliedVoltage = Volts.mutable(0);
pivotPosition = Radians.mutable(0);
pivotVelocity = RadiansPerSecond.mutable(0);
routine = new SysIdRoutine(
ManipulatorPivotConstants.kSysIDConfig,
new SysIdRoutine.Mechanism(
pivotMotor::setVoltage,
(log) -> {
log.motor("armMotor")
.voltage(appliedVoltage.mut_replace(
pivotMotor.get() * RobotController.getBatteryVoltage(), Volts
))
.angularPosition(pivotPosition.mut_replace(
getEncoderPosition(), Radians
))
.angularVelocity(pivotVelocity.mut_replace(
getEncoderVelocity(), RadiansPerSecond
));
},
this
)
);
}
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
return routine.quasistatic(direction);
}
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
return routine.dynamic(direction);
}
}

View File

@@ -0,0 +1,38 @@
{
"fileName": "PathplannerLib-2025.2.1.json",
"name": "PathplannerLib",
"version": "2025.2.1",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
"javaDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.2.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.2.1",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal",
"linuxathena",
"linuxarm32",
"linuxarm64"
]
}
]
}

View File

@@ -1,50 +1,50 @@
{
"fileName": "Phoenix5-5.34.0-beta-4.json",
"fileName": "Phoenix5-5.35.1.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"frcYear": "2025",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-latest.json",
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-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-frc2025-beta-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json"
"offlineFileName": "Phoenix6-frc2025-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json"
}
],
"conflictsWith": [
{
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.",
"offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json"
"offlineFileName": "Phoenix6-replay-frc2025-latest.json"
},
{
"uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df",
"errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.",
"offlineFileName": "Phoenix5-replay-frc2025-beta-latest.json"
"offlineFileName": "Phoenix5-replay-frc2025-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.34.0-beta-4"
"version": "5.35.1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.34.0-beta-4"
"version": "5.35.1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -74,7 +74,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -106,7 +106,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -122,7 +122,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -138,7 +138,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -154,7 +154,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.34.0-beta-4",
"version": "5.35.1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,

View File

@@ -1,32 +1,32 @@
{
"fileName": "Phoenix6-25.0.0-beta-4.json",
"fileName": "Phoenix6-25.2.1.json",
"name": "CTRE-Phoenix (v6)",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"frcYear": "2025",
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json",
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json",
"conflictsWith": [
{
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.",
"offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json"
"offlineFileName": "Phoenix6-replay-frc2025-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java",
"version": "25.0.0-beta-4"
"version": "25.2.1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix6",
"artifactId": "api-cpp",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -40,7 +40,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -54,7 +54,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "api-cpp-sim",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -68,7 +68,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -82,7 +82,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -96,7 +96,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -110,7 +110,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -124,7 +124,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -138,7 +138,21 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -152,21 +166,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "25.0.0-beta-4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -180,7 +180,21 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
"version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -196,7 +210,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -212,7 +226,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_PhoenixTools",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -228,7 +242,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -244,7 +258,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -260,7 +274,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -276,7 +290,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -292,7 +306,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -308,7 +322,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimCANCoder",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -324,7 +338,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -337,10 +351,26 @@
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
"version": "25.2.1",
"libName": "CTRE_SimProTalonFXS",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "25.0.0-beta-4",
"version": "25.2.1",
"libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers",
"sharedLibrary": true,
@@ -355,9 +385,9 @@
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
"version": "25.0.0-beta-4",
"libName": "CTRE_SimProCANrange",
"artifactId": "simProPigeon2",
"version": "25.2.1",
"libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
@@ -371,9 +401,9 @@
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "25.0.0-beta-4",
"libName": "CTRE_SimProPigeon2",
"artifactId": "simProCANrange",
"version": "25.2.1",
"libName": "CTRE_SimProCANrange",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,

View File

@@ -1,7 +1,7 @@
{
"fileName": "REVLib-2025.0.0-beta-3.json",
"fileName": "REVLib-2025.0.1.json",
"name": "REVLib",
"version": "2025.0.0-beta-3",
"version": "2025.0.1",
"frcYear": "2025",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
@@ -12,19 +12,18 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2025.0.0-beta-3"
"version": "2025.0.1"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2025.0.0-beta-3",
"version": "2025.0.1",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
@@ -37,14 +36,13 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2025.0.0-beta-3",
"version": "2025.0.1",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
@@ -55,14 +53,13 @@
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2025.0.0-beta-3",
"version": "2025.0.1",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",

View File

@@ -0,0 +1,71 @@
{
"fileName": "Studica-2025.0.1.json",
"name": "Studica",
"version": "2025.0.1",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2025",
"mavenUrls": [
"https://dev.studica.com/maven/release/2025/"
],
"jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.1.json",
"cppDependencies": [
{
"artifactId": "Studica-cpp",
"binaryPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"groupId": "com.studica.frc",
"headerClassifier": "headers",
"libName": "Studica",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"version": "2025.0.1"
},
{
"artifactId": "Studica-driver",
"binaryPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"groupId": "com.studica.frc",
"headerClassifier": "headers",
"libName": "StudicaDriver",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"version": "2025.0.1"
}
],
"javaDependencies": [
{
"artifactId": "Studica-java",
"groupId": "com.studica.frc",
"version": "2025.0.1"
}
],
"jniDependencies": [
{
"artifactId": "Studica-driver",
"groupId": "com.studica.frc",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"version": "2025.0.1"
}
]
}