Initial Commit, REV template
This commit is contained in:
commit
cfd538f97e
184
.gitignore
vendored
Normal file
184
.gitignore
vendored
Normal file
@ -0,0 +1,184 @@
|
|||||||
|
# This gitignore has been specially created by the WPILib team.
|
||||||
|
# If you remove items from this file, intellisense might break.
|
||||||
|
|
||||||
|
### C++ ###
|
||||||
|
# Prerequisites
|
||||||
|
*.d
|
||||||
|
|
||||||
|
# Compiled Object files
|
||||||
|
*.slo
|
||||||
|
*.lo
|
||||||
|
*.o
|
||||||
|
*.obj
|
||||||
|
|
||||||
|
# Precompiled Headers
|
||||||
|
*.gch
|
||||||
|
*.pch
|
||||||
|
|
||||||
|
# Compiled Dynamic libraries
|
||||||
|
*.so
|
||||||
|
*.dylib
|
||||||
|
*.dll
|
||||||
|
|
||||||
|
# Fortran module files
|
||||||
|
*.mod
|
||||||
|
*.smod
|
||||||
|
|
||||||
|
# Compiled Static libraries
|
||||||
|
*.lai
|
||||||
|
*.la
|
||||||
|
*.a
|
||||||
|
*.lib
|
||||||
|
|
||||||
|
# Executables
|
||||||
|
*.exe
|
||||||
|
*.out
|
||||||
|
*.app
|
||||||
|
|
||||||
|
### Java ###
|
||||||
|
# Compiled class file
|
||||||
|
*.class
|
||||||
|
|
||||||
|
# Log file
|
||||||
|
*.log
|
||||||
|
|
||||||
|
# BlueJ files
|
||||||
|
*.ctxt
|
||||||
|
|
||||||
|
# Mobile Tools for Java (J2ME)
|
||||||
|
.mtj.tmp/
|
||||||
|
|
||||||
|
# Package Files #
|
||||||
|
*.jar
|
||||||
|
*.war
|
||||||
|
*.nar
|
||||||
|
*.ear
|
||||||
|
*.zip
|
||||||
|
*.tar.gz
|
||||||
|
*.rar
|
||||||
|
|
||||||
|
# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml
|
||||||
|
hs_err_pid*
|
||||||
|
|
||||||
|
### Linux ###
|
||||||
|
*~
|
||||||
|
|
||||||
|
# temporary files which can be created if a process still has a handle open of a deleted file
|
||||||
|
.fuse_hidden*
|
||||||
|
|
||||||
|
# KDE directory preferences
|
||||||
|
.directory
|
||||||
|
|
||||||
|
# Linux trash folder which might appear on any partition or disk
|
||||||
|
.Trash-*
|
||||||
|
|
||||||
|
# .nfs files are created when an open file is removed but is still being accessed
|
||||||
|
.nfs*
|
||||||
|
|
||||||
|
### macOS ###
|
||||||
|
# General
|
||||||
|
.DS_Store
|
||||||
|
.AppleDouble
|
||||||
|
.LSOverride
|
||||||
|
|
||||||
|
# Icon must end with two \r
|
||||||
|
Icon
|
||||||
|
|
||||||
|
# Thumbnails
|
||||||
|
._*
|
||||||
|
|
||||||
|
# Files that might appear in the root of a volume
|
||||||
|
.DocumentRevisions-V100
|
||||||
|
.fseventsd
|
||||||
|
.Spotlight-V100
|
||||||
|
.TemporaryItems
|
||||||
|
.Trashes
|
||||||
|
.VolumeIcon.icns
|
||||||
|
.com.apple.timemachine.donotpresent
|
||||||
|
|
||||||
|
# Directories potentially created on remote AFP share
|
||||||
|
.AppleDB
|
||||||
|
.AppleDesktop
|
||||||
|
Network Trash Folder
|
||||||
|
Temporary Items
|
||||||
|
.apdisk
|
||||||
|
|
||||||
|
### VisualStudioCode ###
|
||||||
|
.vscode/*
|
||||||
|
!.vscode/settings.json
|
||||||
|
!.vscode/tasks.json
|
||||||
|
!.vscode/launch.json
|
||||||
|
!.vscode/extensions.json
|
||||||
|
|
||||||
|
### Windows ###
|
||||||
|
# Windows thumbnail cache files
|
||||||
|
Thumbs.db
|
||||||
|
ehthumbs.db
|
||||||
|
ehthumbs_vista.db
|
||||||
|
|
||||||
|
# Dump file
|
||||||
|
*.stackdump
|
||||||
|
|
||||||
|
# Folder config file
|
||||||
|
[Dd]esktop.ini
|
||||||
|
|
||||||
|
# Recycle Bin used on file shares
|
||||||
|
$RECYCLE.BIN/
|
||||||
|
|
||||||
|
# Windows Installer files
|
||||||
|
*.cab
|
||||||
|
*.msi
|
||||||
|
*.msix
|
||||||
|
*.msm
|
||||||
|
*.msp
|
||||||
|
|
||||||
|
# Windows shortcuts
|
||||||
|
*.lnk
|
||||||
|
|
||||||
|
### Gradle ###
|
||||||
|
.gradle
|
||||||
|
/build/
|
||||||
|
|
||||||
|
# Ignore Gradle GUI config
|
||||||
|
gradle-app.setting
|
||||||
|
|
||||||
|
# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored)
|
||||||
|
!gradle-wrapper.jar
|
||||||
|
|
||||||
|
# Cache of project
|
||||||
|
.gradletasknamecache
|
||||||
|
|
||||||
|
# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898
|
||||||
|
# gradle/wrapper/gradle-wrapper.properties
|
||||||
|
|
||||||
|
# # VS Code Specific Java Settings
|
||||||
|
# DO NOT REMOVE .classpath and .project
|
||||||
|
.classpath
|
||||||
|
.project
|
||||||
|
.settings/
|
||||||
|
bin/
|
||||||
|
|
||||||
|
# IntelliJ
|
||||||
|
*.iml
|
||||||
|
*.ipr
|
||||||
|
*.iws
|
||||||
|
.idea/
|
||||||
|
out/
|
||||||
|
|
||||||
|
# Fleet
|
||||||
|
.fleet
|
||||||
|
|
||||||
|
# Simulation GUI and other tools window save file
|
||||||
|
networktables.json
|
||||||
|
simgui.json
|
||||||
|
*-window.json
|
||||||
|
|
||||||
|
# Simulation data log directory
|
||||||
|
logs/
|
||||||
|
|
||||||
|
# Folder that has CTRE Phoenix Sim device config storage
|
||||||
|
ctre_sim/
|
||||||
|
|
||||||
|
# clangd
|
||||||
|
/.cache
|
||||||
|
compile_commands.json
|
21
.vscode/launch.json
vendored
Normal file
21
.vscode/launch.json
vendored
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
{
|
||||||
|
// Use IntelliSense to learn about possible attributes.
|
||||||
|
// Hover to view descriptions of existing attributes.
|
||||||
|
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
|
||||||
|
"version": "0.2.0",
|
||||||
|
"configurations": [
|
||||||
|
|
||||||
|
{
|
||||||
|
"type": "wpilib",
|
||||||
|
"name": "WPILib Desktop Debug",
|
||||||
|
"request": "launch",
|
||||||
|
"desktop": true,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "wpilib",
|
||||||
|
"name": "WPILib roboRIO Debug",
|
||||||
|
"request": "launch",
|
||||||
|
"desktop": false,
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
29
.vscode/settings.json
vendored
Normal file
29
.vscode/settings.json
vendored
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
{
|
||||||
|
"java.configuration.updateBuildConfiguration": "automatic",
|
||||||
|
"java.server.launchMode": "Standard",
|
||||||
|
"files.exclude": {
|
||||||
|
"**/.git": true,
|
||||||
|
"**/.svn": true,
|
||||||
|
"**/.hg": true,
|
||||||
|
"**/CVS": true,
|
||||||
|
"**/.DS_Store": true,
|
||||||
|
"bin/": true,
|
||||||
|
"**/.classpath": true,
|
||||||
|
"**/.project": true,
|
||||||
|
"**/.settings": true,
|
||||||
|
"**/.factorypath": true,
|
||||||
|
"**/*~": true
|
||||||
|
},
|
||||||
|
"java.test.config": [
|
||||||
|
{
|
||||||
|
"name": "WPIlibUnitTests",
|
||||||
|
"workingDirectory": "${workspaceFolder}/build/jni/release",
|
||||||
|
"vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ],
|
||||||
|
"env": {
|
||||||
|
"LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" ,
|
||||||
|
"DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
],
|
||||||
|
"java.test.defaultConfig": "WPIlibUnitTests"
|
||||||
|
}
|
6
.wpilib/wpilib_preferences.json
Normal file
6
.wpilib/wpilib_preferences.json
Normal file
@ -0,0 +1,6 @@
|
|||||||
|
{
|
||||||
|
"enableCppIntellisense": false,
|
||||||
|
"currentLanguage": "java",
|
||||||
|
"projectYear": "2025beta",
|
||||||
|
"teamNumber": 2714
|
||||||
|
}
|
25
LICENSE.txt
Normal file
25
LICENSE.txt
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
Copyright (c) 2018-2023 REV Robotics
|
||||||
|
|
||||||
|
Redistribution and use in source and binary forms, with or without
|
||||||
|
modification, are permitted provided that the following conditions are met:
|
||||||
|
|
||||||
|
1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer.
|
||||||
|
2. 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.
|
||||||
|
3. Neither the name of REV Robotics nor the names of its
|
||||||
|
contributors may be used to endorse or promote products derived from
|
||||||
|
this software without specific prior written permission.
|
||||||
|
|
||||||
|
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||||
|
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER 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.
|
24
WPILib-License.md
Normal file
24
WPILib-License.md
Normal file
@ -0,0 +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.
|
102
build.gradle
Normal file
102
build.gradle
Normal file
@ -0,0 +1,102 @@
|
|||||||
|
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'
|
||||||
|
}
|
BIN
gradle/wrapper/gradle-wrapper.jar
vendored
Normal file
BIN
gradle/wrapper/gradle-wrapper.jar
vendored
Normal file
Binary file not shown.
7
gradle/wrapper/gradle-wrapper.properties
vendored
Normal file
7
gradle/wrapper/gradle-wrapper.properties
vendored
Normal file
@ -0,0 +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
|
252
gradlew
vendored
Normal file
252
gradlew
vendored
Normal file
@ -0,0 +1,252 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
|
||||||
|
#
|
||||||
|
# Copyright © 2015-2021 the original authors.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# https://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
#
|
||||||
|
# SPDX-License-Identifier: Apache-2.0
|
||||||
|
#
|
||||||
|
|
||||||
|
##############################################################################
|
||||||
|
#
|
||||||
|
# Gradle start up script for POSIX generated by Gradle.
|
||||||
|
#
|
||||||
|
# Important for running:
|
||||||
|
#
|
||||||
|
# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is
|
||||||
|
# noncompliant, but you have some other compliant shell such as ksh or
|
||||||
|
# bash, then to run this script, type that shell name before the whole
|
||||||
|
# command line, like:
|
||||||
|
#
|
||||||
|
# ksh Gradle
|
||||||
|
#
|
||||||
|
# Busybox and similar reduced shells will NOT work, because this script
|
||||||
|
# requires all of these POSIX shell features:
|
||||||
|
# * functions;
|
||||||
|
# * expansions «$var», «${var}», «${var:-default}», «${var+SET}»,
|
||||||
|
# «${var#prefix}», «${var%suffix}», and «$( cmd )»;
|
||||||
|
# * compound commands having a testable exit status, especially «case»;
|
||||||
|
# * various built-in commands including «command», «set», and «ulimit».
|
||||||
|
#
|
||||||
|
# Important for patching:
|
||||||
|
#
|
||||||
|
# (2) This script targets any POSIX shell, so it avoids extensions provided
|
||||||
|
# by Bash, Ksh, etc; in particular arrays are avoided.
|
||||||
|
#
|
||||||
|
# The "traditional" practice of packing multiple parameters into a
|
||||||
|
# space-separated string is a well documented source of bugs and security
|
||||||
|
# problems, so this is (mostly) avoided, by progressively accumulating
|
||||||
|
# options in "$@", and eventually passing that to Java.
|
||||||
|
#
|
||||||
|
# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS,
|
||||||
|
# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly;
|
||||||
|
# see the in-line comments for details.
|
||||||
|
#
|
||||||
|
# There are tweaks for specific operating systems such as AIX, CygWin,
|
||||||
|
# Darwin, MinGW, and NonStop.
|
||||||
|
#
|
||||||
|
# (3) This script is generated from the Groovy template
|
||||||
|
# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt
|
||||||
|
# within the Gradle project.
|
||||||
|
#
|
||||||
|
# You can find Gradle at https://github.com/gradle/gradle/.
|
||||||
|
#
|
||||||
|
##############################################################################
|
||||||
|
|
||||||
|
# Attempt to set APP_HOME
|
||||||
|
|
||||||
|
# Resolve links: $0 may be a link
|
||||||
|
app_path=$0
|
||||||
|
|
||||||
|
# Need this for daisy-chained symlinks.
|
||||||
|
while
|
||||||
|
APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path
|
||||||
|
[ -h "$app_path" ]
|
||||||
|
do
|
||||||
|
ls=$( ls -ld "$app_path" )
|
||||||
|
link=${ls#*' -> '}
|
||||||
|
case $link in #(
|
||||||
|
/*) app_path=$link ;; #(
|
||||||
|
*) app_path=$APP_HOME$link ;;
|
||||||
|
esac
|
||||||
|
done
|
||||||
|
|
||||||
|
# This is normally unused
|
||||||
|
# shellcheck disable=SC2034
|
||||||
|
APP_BASE_NAME=${0##*/}
|
||||||
|
# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036)
|
||||||
|
APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s
|
||||||
|
' "$PWD" ) || exit
|
||||||
|
|
||||||
|
# Use the maximum available, or set MAX_FD != -1 to use that value.
|
||||||
|
MAX_FD=maximum
|
||||||
|
|
||||||
|
warn () {
|
||||||
|
echo "$*"
|
||||||
|
} >&2
|
||||||
|
|
||||||
|
die () {
|
||||||
|
echo
|
||||||
|
echo "$*"
|
||||||
|
echo
|
||||||
|
exit 1
|
||||||
|
} >&2
|
||||||
|
|
||||||
|
# OS specific support (must be 'true' or 'false').
|
||||||
|
cygwin=false
|
||||||
|
msys=false
|
||||||
|
darwin=false
|
||||||
|
nonstop=false
|
||||||
|
case "$( uname )" in #(
|
||||||
|
CYGWIN* ) cygwin=true ;; #(
|
||||||
|
Darwin* ) darwin=true ;; #(
|
||||||
|
MSYS* | MINGW* ) msys=true ;; #(
|
||||||
|
NONSTOP* ) nonstop=true ;;
|
||||||
|
esac
|
||||||
|
|
||||||
|
CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar
|
||||||
|
|
||||||
|
|
||||||
|
# Determine the Java command to use to start the JVM.
|
||||||
|
if [ -n "$JAVA_HOME" ] ; then
|
||||||
|
if [ -x "$JAVA_HOME/jre/sh/java" ] ; then
|
||||||
|
# IBM's JDK on AIX uses strange locations for the executables
|
||||||
|
JAVACMD=$JAVA_HOME/jre/sh/java
|
||||||
|
else
|
||||||
|
JAVACMD=$JAVA_HOME/bin/java
|
||||||
|
fi
|
||||||
|
if [ ! -x "$JAVACMD" ] ; then
|
||||||
|
die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME
|
||||||
|
|
||||||
|
Please set the JAVA_HOME variable in your environment to match the
|
||||||
|
location of your Java installation."
|
||||||
|
fi
|
||||||
|
else
|
||||||
|
JAVACMD=java
|
||||||
|
if ! command -v java >/dev/null 2>&1
|
||||||
|
then
|
||||||
|
die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
|
||||||
|
|
||||||
|
Please set the JAVA_HOME variable in your environment to match the
|
||||||
|
location of your Java installation."
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Increase the maximum file descriptors if we can.
|
||||||
|
if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then
|
||||||
|
case $MAX_FD in #(
|
||||||
|
max*)
|
||||||
|
# In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked.
|
||||||
|
# shellcheck disable=SC2039,SC3045
|
||||||
|
MAX_FD=$( ulimit -H -n ) ||
|
||||||
|
warn "Could not query maximum file descriptor limit"
|
||||||
|
esac
|
||||||
|
case $MAX_FD in #(
|
||||||
|
'' | soft) :;; #(
|
||||||
|
*)
|
||||||
|
# In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked.
|
||||||
|
# shellcheck disable=SC2039,SC3045
|
||||||
|
ulimit -n "$MAX_FD" ||
|
||||||
|
warn "Could not set maximum file descriptor limit to $MAX_FD"
|
||||||
|
esac
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Collect all arguments for the java command, stacking in reverse order:
|
||||||
|
# * args from the command line
|
||||||
|
# * the main class name
|
||||||
|
# * -classpath
|
||||||
|
# * -D...appname settings
|
||||||
|
# * --module-path (only if needed)
|
||||||
|
# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables.
|
||||||
|
|
||||||
|
# For Cygwin or MSYS, switch paths to Windows format before running java
|
||||||
|
if "$cygwin" || "$msys" ; then
|
||||||
|
APP_HOME=$( cygpath --path --mixed "$APP_HOME" )
|
||||||
|
CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" )
|
||||||
|
|
||||||
|
JAVACMD=$( cygpath --unix "$JAVACMD" )
|
||||||
|
|
||||||
|
# Now convert the arguments - kludge to limit ourselves to /bin/sh
|
||||||
|
for arg do
|
||||||
|
if
|
||||||
|
case $arg in #(
|
||||||
|
-*) false ;; # don't mess with options #(
|
||||||
|
/?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath
|
||||||
|
[ -e "$t" ] ;; #(
|
||||||
|
*) false ;;
|
||||||
|
esac
|
||||||
|
then
|
||||||
|
arg=$( cygpath --path --ignore --mixed "$arg" )
|
||||||
|
fi
|
||||||
|
# Roll the args list around exactly as many times as the number of
|
||||||
|
# args, so each arg winds up back in the position where it started, but
|
||||||
|
# possibly modified.
|
||||||
|
#
|
||||||
|
# NB: a `for` loop captures its iteration list before it begins, so
|
||||||
|
# changing the positional parameters here affects neither the number of
|
||||||
|
# iterations, nor the values presented in `arg`.
|
||||||
|
shift # remove old arg
|
||||||
|
set -- "$@" "$arg" # push replacement arg
|
||||||
|
done
|
||||||
|
fi
|
||||||
|
|
||||||
|
|
||||||
|
# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script.
|
||||||
|
DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"'
|
||||||
|
|
||||||
|
# Collect all arguments for the java command:
|
||||||
|
# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments,
|
||||||
|
# and any embedded shellness will be escaped.
|
||||||
|
# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be
|
||||||
|
# treated as '${Hostname}' itself on the command line.
|
||||||
|
|
||||||
|
set -- \
|
||||||
|
"-Dorg.gradle.appname=$APP_BASE_NAME" \
|
||||||
|
-classpath "$CLASSPATH" \
|
||||||
|
org.gradle.wrapper.GradleWrapperMain \
|
||||||
|
"$@"
|
||||||
|
|
||||||
|
# Stop when "xargs" is not available.
|
||||||
|
if ! command -v xargs >/dev/null 2>&1
|
||||||
|
then
|
||||||
|
die "xargs is not available"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Use "xargs" to parse quoted args.
|
||||||
|
#
|
||||||
|
# With -n1 it outputs one arg per line, with the quotes and backslashes removed.
|
||||||
|
#
|
||||||
|
# In Bash we could simply go:
|
||||||
|
#
|
||||||
|
# readarray ARGS < <( xargs -n1 <<<"$var" ) &&
|
||||||
|
# set -- "${ARGS[@]}" "$@"
|
||||||
|
#
|
||||||
|
# but POSIX shell has neither arrays nor command substitution, so instead we
|
||||||
|
# post-process each arg (as a line of input to sed) to backslash-escape any
|
||||||
|
# character that might be a shell metacharacter, then use eval to reverse
|
||||||
|
# that process (while maintaining the separation between arguments), and wrap
|
||||||
|
# the whole thing up as a single "set" statement.
|
||||||
|
#
|
||||||
|
# This will of course break if any of these variables contains a newline or
|
||||||
|
# an unmatched quote.
|
||||||
|
#
|
||||||
|
|
||||||
|
eval "set -- $(
|
||||||
|
printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" |
|
||||||
|
xargs -n1 |
|
||||||
|
sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' |
|
||||||
|
tr '\n' ' '
|
||||||
|
)" '"$@"'
|
||||||
|
|
||||||
|
exec "$JAVACMD" "$@"
|
94
gradlew.bat
vendored
Normal file
94
gradlew.bat
vendored
Normal file
@ -0,0 +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
|
30
settings.gradle
Normal file
30
settings.gradle
Normal file
@ -0,0 +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");
|
3
src/main/deploy/example.txt
Normal file
3
src/main/deploy/example.txt
Normal file
@ -0,0 +1,3 @@
|
|||||||
|
Files placed in this directory will be deployed to the RoboRIO into the
|
||||||
|
'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function
|
||||||
|
to get a proper path relative to the deploy directory.
|
56
src/main/java/frc/robot/Configs.java
Normal file
56
src/main/java/frc/robot/Configs.java
Normal file
@ -0,0 +1,56 @@
|
|||||||
|
package frc.robot;
|
||||||
|
|
||||||
|
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||||
|
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
|
||||||
|
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||||
|
|
||||||
|
import frc.robot.Constants.ModuleConstants;
|
||||||
|
|
||||||
|
public final class Configs {
|
||||||
|
public static final class MAXSwerveModule {
|
||||||
|
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 = ModuleConstants.kWheelDiameterMeters * Math.PI
|
||||||
|
/ ModuleConstants.kDrivingMotorReduction;
|
||||||
|
double turningFactor = 2 * Math.PI;
|
||||||
|
double drivingVelocityFeedForward = 1 / ModuleConstants.kDriveWheelFreeSpeedRps;
|
||||||
|
|
||||||
|
drivingConfig
|
||||||
|
.idleMode(IdleMode.kBrake)
|
||||||
|
.smartCurrentLimit(50);
|
||||||
|
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);
|
||||||
|
|
||||||
|
turningConfig
|
||||||
|
.idleMode(IdleMode.kBrake)
|
||||||
|
.smartCurrentLimit(20);
|
||||||
|
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
|
||||||
|
turningConfig.closedLoop
|
||||||
|
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
|
||||||
|
// These are example gains you may need to them for your own robot!
|
||||||
|
.pid(1, 0, 0)
|
||||||
|
.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);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
102
src/main/java/frc/robot/Constants.java
Normal file
102
src/main/java/frc/robot/Constants.java
Normal file
@ -0,0 +1,102 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.geometry.Translation2d;
|
||||||
|
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
|
||||||
|
import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||||
|
import edu.wpi.first.math.util.Units;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The Constants class provides a convenient place for teams to hold robot-wide
|
||||||
|
* numerical or boolean
|
||||||
|
* constants. This class should not be used for any other purpose. All constants
|
||||||
|
* should be declared
|
||||||
|
* globally (i.e. public static). Do not put anything functional in this class.
|
||||||
|
*
|
||||||
|
* <p>
|
||||||
|
* It is advised to statically import this class (or one of its inner classes)
|
||||||
|
* wherever the
|
||||||
|
* constants are needed, to reduce verbosity.
|
||||||
|
*/
|
||||||
|
public final class Constants {
|
||||||
|
public static final class DriveConstants {
|
||||||
|
// Driving Parameters - Note that these are not the maximum capable speeds of
|
||||||
|
// the robot, rather the allowed maximum speeds
|
||||||
|
public static final double kMaxSpeedMetersPerSecond = 4.8;
|
||||||
|
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
||||||
|
|
||||||
|
// Chassis configuration
|
||||||
|
public static final double kTrackWidth = Units.inchesToMeters(26.5);
|
||||||
|
// Distance between centers of right and left wheels on robot
|
||||||
|
public static final double kWheelBase = Units.inchesToMeters(26.5);
|
||||||
|
// Distance between front and back wheels on robot
|
||||||
|
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
|
||||||
|
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
|
||||||
|
new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
|
||||||
|
new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
|
||||||
|
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
|
||||||
|
// 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 kFrontLeftTurningCanId = 10;
|
||||||
|
public static final int kRearLeftTurningCanId = 12;
|
||||||
|
public static final int kFrontRightTurningCanId = 14;
|
||||||
|
public static final int kRearRightTurningCanId = 16;
|
||||||
|
|
||||||
|
public static final boolean kGyroReversed = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
public static final class ModuleConstants {
|
||||||
|
// The MAXSwerve module can be configured with one of three pinion gears: 12T,
|
||||||
|
// 13T, or 14T. This changes the drive speed of the module (a pinion gear with
|
||||||
|
// more teeth will result in a robot that drives faster).
|
||||||
|
public static final int kDrivingMotorPinionTeeth = 14;
|
||||||
|
|
||||||
|
// Calculations required for driving motor conversion factors and feed forward
|
||||||
|
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
|
||||||
|
public static final double kWheelDiameterMeters = 0.0762;
|
||||||
|
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
|
||||||
|
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15
|
||||||
|
// teeth on the bevel pinion
|
||||||
|
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
|
||||||
|
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
|
||||||
|
/ kDrivingMotorReduction;
|
||||||
|
}
|
||||||
|
|
||||||
|
public static final class OIConstants {
|
||||||
|
public static final int kDriverControllerPort = 0;
|
||||||
|
public static final double kDriveDeadband = 0.05;
|
||||||
|
}
|
||||||
|
|
||||||
|
public static final class AutoConstants {
|
||||||
|
public static final double kMaxSpeedMetersPerSecond = 3;
|
||||||
|
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
|
||||||
|
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
|
||||||
|
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
|
||||||
|
|
||||||
|
public static final double kPXController = 1;
|
||||||
|
public static final double kPYController = 1;
|
||||||
|
public static final double kPThetaController = 1;
|
||||||
|
|
||||||
|
// Constraint for the motion profiled robot angle controller
|
||||||
|
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
|
||||||
|
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static final class NeoMotorConstants {
|
||||||
|
public static final double kFreeSpeedRpm = 5676;
|
||||||
|
}
|
||||||
|
}
|
25
src/main/java/frc/robot/Main.java
Normal file
25
src/main/java/frc/robot/Main.java
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.RobotBase;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||||
|
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||||
|
* call.
|
||||||
|
*/
|
||||||
|
public final class Main {
|
||||||
|
private Main() {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Main initialization function. Do not perform any initialization here.
|
||||||
|
*
|
||||||
|
* <p>If you change your main robot class, change the parameter type.
|
||||||
|
*/
|
||||||
|
public static void main(String... args) {
|
||||||
|
RobotBase.startRobot(Robot::new);
|
||||||
|
}
|
||||||
|
}
|
102
src/main/java/frc/robot/Robot.java
Normal file
102
src/main/java/frc/robot/Robot.java
Normal file
@ -0,0 +1,102 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.TimedRobot;
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The VM is configured to automatically run this class, and to call the functions corresponding to
|
||||||
|
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
|
||||||
|
* the package after creating this project, you must also update the build.gradle file in the
|
||||||
|
* project.
|
||||||
|
*/
|
||||||
|
public class Robot extends TimedRobot {
|
||||||
|
private Command m_autonomousCommand;
|
||||||
|
|
||||||
|
private RobotContainer m_robotContainer;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This function is run when the robot is first started up and should be used for any
|
||||||
|
* initialization code.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public void robotInit() {
|
||||||
|
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||||||
|
// autonomous chooser on the dashboard.
|
||||||
|
m_robotContainer = new RobotContainer();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
|
||||||
|
* that you want ran during disabled, autonomous, teleoperated and test.
|
||||||
|
*
|
||||||
|
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||||
|
* SmartDashboard integrated updating.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public void robotPeriodic() {
|
||||||
|
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
|
||||||
|
// commands, running already-scheduled commands, removing finished or interrupted commands,
|
||||||
|
// and running subsystem periodic() methods. This must be called from the robot's periodic
|
||||||
|
// block in order for anything in the Command-based framework to work.
|
||||||
|
CommandScheduler.getInstance().run();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** This function is called once each time the robot enters Disabled mode. */
|
||||||
|
@Override
|
||||||
|
public void disabledInit() {}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void disabledPeriodic() {}
|
||||||
|
|
||||||
|
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||||
|
@Override
|
||||||
|
public void autonomousInit() {
|
||||||
|
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||||
|
|
||||||
|
/*
|
||||||
|
* String autoSelected = SmartDashboard.getString("Auto Selector",
|
||||||
|
* "Default"); switch(autoSelected) { case "My Auto": autonomousCommand
|
||||||
|
* = new MyAutoCommand(); break; case "Default Auto": default:
|
||||||
|
* autonomousCommand = new ExampleCommand(); break; }
|
||||||
|
*/
|
||||||
|
|
||||||
|
// schedule the autonomous command (example)
|
||||||
|
if (m_autonomousCommand != null) {
|
||||||
|
m_autonomousCommand.schedule();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** This function is called periodically during autonomous. */
|
||||||
|
@Override
|
||||||
|
public void autonomousPeriodic() {}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void teleopInit() {
|
||||||
|
// This makes sure that the autonomous stops running when
|
||||||
|
// teleop starts running. If you want the autonomous to
|
||||||
|
// continue until interrupted by another command, remove
|
||||||
|
// this line or comment it out.
|
||||||
|
if (m_autonomousCommand != null) {
|
||||||
|
m_autonomousCommand.cancel();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** This function is called periodically during operator control. */
|
||||||
|
@Override
|
||||||
|
public void teleopPeriodic() {}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void testInit() {
|
||||||
|
// Cancels all running commands at the start of test mode.
|
||||||
|
CommandScheduler.getInstance().cancelAll();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** This function is called periodically during test mode. */
|
||||||
|
@Override
|
||||||
|
public void testPeriodic() {}
|
||||||
|
}
|
122
src/main/java/frc/robot/RobotContainer.java
Normal file
122
src/main/java/frc/robot/RobotContainer.java
Normal file
@ -0,0 +1,122 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.MathUtil;
|
||||||
|
import edu.wpi.first.math.controller.PIDController;
|
||||||
|
import edu.wpi.first.math.controller.ProfiledPIDController;
|
||||||
|
import edu.wpi.first.math.geometry.Pose2d;
|
||||||
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
|
import edu.wpi.first.math.geometry.Translation2d;
|
||||||
|
import edu.wpi.first.math.trajectory.Trajectory;
|
||||||
|
import edu.wpi.first.math.trajectory.TrajectoryConfig;
|
||||||
|
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
|
||||||
|
import edu.wpi.first.wpilibj.XboxController;
|
||||||
|
import edu.wpi.first.wpilibj.PS4Controller.Button;
|
||||||
|
import frc.robot.Constants.AutoConstants;
|
||||||
|
import frc.robot.Constants.DriveConstants;
|
||||||
|
import frc.robot.Constants.OIConstants;
|
||||||
|
import frc.robot.subsystems.DriveSubsystem;
|
||||||
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||||
|
import edu.wpi.first.wpilibj2.command.SwerveControllerCommand;
|
||||||
|
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||||
|
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||||
|
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||||
|
* (including subsystems, commands, and button mappings) should be declared here.
|
||||||
|
*/
|
||||||
|
public class RobotContainer {
|
||||||
|
// The robot's subsystems
|
||||||
|
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
|
||||||
|
|
||||||
|
// The driver's controller
|
||||||
|
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||||
|
*/
|
||||||
|
public RobotContainer() {
|
||||||
|
// Configure the button bindings
|
||||||
|
configureButtonBindings();
|
||||||
|
|
||||||
|
// Configure default commands
|
||||||
|
m_robotDrive.setDefaultCommand(
|
||||||
|
// The left stick controls translation of the robot.
|
||||||
|
// Turning is controlled by the X axis of the right stick.
|
||||||
|
new RunCommand(
|
||||||
|
() -> m_robotDrive.drive(
|
||||||
|
-MathUtil.applyDeadband(m_driverController.getLeftY(), OIConstants.kDriveDeadband),
|
||||||
|
-MathUtil.applyDeadband(m_driverController.getLeftX(), OIConstants.kDriveDeadband),
|
||||||
|
-MathUtil.applyDeadband(m_driverController.getRightX(), OIConstants.kDriveDeadband),
|
||||||
|
true),
|
||||||
|
m_robotDrive));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Use this method to define your button->command mappings. Buttons can be
|
||||||
|
* created by
|
||||||
|
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its
|
||||||
|
* subclasses ({@link
|
||||||
|
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then calling
|
||||||
|
* passing it to a
|
||||||
|
* {@link JoystickButton}.
|
||||||
|
*/
|
||||||
|
private void configureButtonBindings() {
|
||||||
|
new JoystickButton(m_driverController, Button.kR1.value)
|
||||||
|
.whileTrue(new RunCommand(
|
||||||
|
() -> m_robotDrive.setX(),
|
||||||
|
m_robotDrive));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||||
|
*
|
||||||
|
* @return the command to run in autonomous
|
||||||
|
*/
|
||||||
|
public Command getAutonomousCommand() {
|
||||||
|
// Create config for trajectory
|
||||||
|
TrajectoryConfig config = new TrajectoryConfig(
|
||||||
|
AutoConstants.kMaxSpeedMetersPerSecond,
|
||||||
|
AutoConstants.kMaxAccelerationMetersPerSecondSquared)
|
||||||
|
// Add kinematics to ensure max speed is actually obeyed
|
||||||
|
.setKinematics(DriveConstants.kDriveKinematics);
|
||||||
|
|
||||||
|
// An example trajectory to follow. All units in meters.
|
||||||
|
Trajectory exampleTrajectory = TrajectoryGenerator.generateTrajectory(
|
||||||
|
// Start at the origin facing the +X direction
|
||||||
|
new Pose2d(0, 0, new Rotation2d(0)),
|
||||||
|
// Pass through these two interior waypoints, making an 's' curve path
|
||||||
|
List.of(new Translation2d(1, 1), new Translation2d(2, -1)),
|
||||||
|
// End 3 meters straight ahead of where we started, facing forward
|
||||||
|
new Pose2d(3, 0, new Rotation2d(0)),
|
||||||
|
config);
|
||||||
|
|
||||||
|
var thetaController = new ProfiledPIDController(
|
||||||
|
AutoConstants.kPThetaController, 0, 0, AutoConstants.kThetaControllerConstraints);
|
||||||
|
thetaController.enableContinuousInput(-Math.PI, Math.PI);
|
||||||
|
|
||||||
|
SwerveControllerCommand swerveControllerCommand = new SwerveControllerCommand(
|
||||||
|
exampleTrajectory,
|
||||||
|
m_robotDrive::getPose, // Functional interface to feed supplier
|
||||||
|
DriveConstants.kDriveKinematics,
|
||||||
|
|
||||||
|
// Position controllers
|
||||||
|
new PIDController(AutoConstants.kPXController, 0, 0),
|
||||||
|
new PIDController(AutoConstants.kPYController, 0, 0),
|
||||||
|
thetaController,
|
||||||
|
m_robotDrive::setModuleStates,
|
||||||
|
m_robotDrive);
|
||||||
|
|
||||||
|
// Reset odometry to the starting pose of the trajectory.
|
||||||
|
m_robotDrive.resetOdometry(exampleTrajectory.getInitialPose());
|
||||||
|
|
||||||
|
// Run path following command, then stop at the end.
|
||||||
|
return swerveControllerCommand.andThen(() -> m_robotDrive.drive(0, 0, 0, false));
|
||||||
|
}
|
||||||
|
}
|
180
src/main/java/frc/robot/subsystems/DriveSubsystem.java
Normal file
180
src/main/java/frc/robot/subsystems/DriveSubsystem.java
Normal file
@ -0,0 +1,180 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
|
import edu.wpi.first.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 frc.robot.Constants.DriveConstants;
|
||||||
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
|
public class DriveSubsystem extends SubsystemBase {
|
||||||
|
// Create MAXSwerveModules
|
||||||
|
private final MAXSwerveModule m_frontLeft = new MAXSwerveModule(
|
||||||
|
DriveConstants.kFrontLeftDrivingCanId,
|
||||||
|
DriveConstants.kFrontLeftTurningCanId,
|
||||||
|
DriveConstants.kFrontLeftChassisAngularOffset);
|
||||||
|
|
||||||
|
private final MAXSwerveModule m_frontRight = new MAXSwerveModule(
|
||||||
|
DriveConstants.kFrontRightDrivingCanId,
|
||||||
|
DriveConstants.kFrontRightTurningCanId,
|
||||||
|
DriveConstants.kFrontRightChassisAngularOffset);
|
||||||
|
|
||||||
|
private final MAXSwerveModule m_rearLeft = new MAXSwerveModule(
|
||||||
|
DriveConstants.kRearLeftDrivingCanId,
|
||||||
|
DriveConstants.kRearLeftTurningCanId,
|
||||||
|
DriveConstants.kBackLeftChassisAngularOffset);
|
||||||
|
|
||||||
|
private final MAXSwerveModule m_rearRight = new MAXSwerveModule(
|
||||||
|
DriveConstants.kRearRightDrivingCanId,
|
||||||
|
DriveConstants.kRearRightTurningCanId,
|
||||||
|
DriveConstants.kBackRightChassisAngularOffset);
|
||||||
|
|
||||||
|
// The gyro sensor
|
||||||
|
private final ADIS16470_IMU m_gyro = new ADIS16470_IMU();
|
||||||
|
|
||||||
|
// Odometry class for tracking robot pose
|
||||||
|
SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(
|
||||||
|
DriveConstants.kDriveKinematics,
|
||||||
|
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
|
||||||
|
new SwerveModulePosition[] {
|
||||||
|
m_frontLeft.getPosition(),
|
||||||
|
m_frontRight.getPosition(),
|
||||||
|
m_rearLeft.getPosition(),
|
||||||
|
m_rearRight.getPosition()
|
||||||
|
});
|
||||||
|
|
||||||
|
/** Creates a new DriveSubsystem. */
|
||||||
|
public DriveSubsystem() {
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void periodic() {
|
||||||
|
// Update the odometry in the periodic block
|
||||||
|
m_odometry.update(
|
||||||
|
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
|
||||||
|
new SwerveModulePosition[] {
|
||||||
|
m_frontLeft.getPosition(),
|
||||||
|
m_frontRight.getPosition(),
|
||||||
|
m_rearLeft.getPosition(),
|
||||||
|
m_rearRight.getPosition()
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the currently-estimated pose of the robot.
|
||||||
|
*
|
||||||
|
* @return The pose.
|
||||||
|
*/
|
||||||
|
public Pose2d getPose() {
|
||||||
|
return m_odometry.getPoseMeters();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Resets the odometry to the specified pose.
|
||||||
|
*
|
||||||
|
* @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()
|
||||||
|
},
|
||||||
|
pose);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Method to drive the robot using joystick info.
|
||||||
|
*
|
||||||
|
* @param xSpeed Speed of the robot in the x direction (forward).
|
||||||
|
* @param ySpeed Speed of the robot in the y direction (sideways).
|
||||||
|
* @param rot Angular rate of the robot.
|
||||||
|
* @param fieldRelative Whether the provided x and y speeds are relative to the
|
||||||
|
* field.
|
||||||
|
*/
|
||||||
|
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||||
|
// Convert the commanded speeds into the correct units for the drivetrain
|
||||||
|
double xSpeedDelivered = xSpeed * DriveConstants.kMaxSpeedMetersPerSecond;
|
||||||
|
double ySpeedDelivered = ySpeed * DriveConstants.kMaxSpeedMetersPerSecond;
|
||||||
|
double rotDelivered = rot * DriveConstants.kMaxAngularSpeed;
|
||||||
|
|
||||||
|
var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
|
||||||
|
fieldRelative
|
||||||
|
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered,
|
||||||
|
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)))
|
||||||
|
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
|
||||||
|
SwerveDriveKinematics.desaturateWheelSpeeds(
|
||||||
|
swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond);
|
||||||
|
m_frontLeft.setDesiredState(swerveModuleStates[0]);
|
||||||
|
m_frontRight.setDesiredState(swerveModuleStates[1]);
|
||||||
|
m_rearLeft.setDesiredState(swerveModuleStates[2]);
|
||||||
|
m_rearRight.setDesiredState(swerveModuleStates[3]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets the wheels into an X formation to prevent movement.
|
||||||
|
*/
|
||||||
|
public void setX() {
|
||||||
|
m_frontLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
|
||||||
|
m_frontRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
|
||||||
|
m_rearLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
|
||||||
|
m_rearRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sets the swerve ModuleStates.
|
||||||
|
*
|
||||||
|
* @param desiredStates The desired SwerveModule states.
|
||||||
|
*/
|
||||||
|
public void setModuleStates(SwerveModuleState[] desiredStates) {
|
||||||
|
SwerveDriveKinematics.desaturateWheelSpeeds(
|
||||||
|
desiredStates, DriveConstants.kMaxSpeedMetersPerSecond);
|
||||||
|
m_frontLeft.setDesiredState(desiredStates[0]);
|
||||||
|
m_frontRight.setDesiredState(desiredStates[1]);
|
||||||
|
m_rearLeft.setDesiredState(desiredStates[2]);
|
||||||
|
m_rearRight.setDesiredState(desiredStates[3]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Resets the drive encoders to currently read a position of 0. */
|
||||||
|
public void resetEncoders() {
|
||||||
|
m_frontLeft.resetEncoders();
|
||||||
|
m_rearLeft.resetEncoders();
|
||||||
|
m_frontRight.resetEncoders();
|
||||||
|
m_rearRight.resetEncoders();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Zeroes the heading of the robot. */
|
||||||
|
public void zeroHeading() {
|
||||||
|
m_gyro.reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the heading of the robot.
|
||||||
|
*
|
||||||
|
* @return the robot's heading in degrees, from -180 to 180
|
||||||
|
*/
|
||||||
|
public double getHeading() {
|
||||||
|
return Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)).getDegrees();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Returns the turn rate of the robot.
|
||||||
|
*
|
||||||
|
* @return The turn rate of the robot, in degrees per second
|
||||||
|
*/
|
||||||
|
public double getTurnRate() {
|
||||||
|
return m_gyro.getRate(IMUAxis.kZ) * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||||
|
}
|
||||||
|
}
|
114
src/main/java/frc/robot/subsystems/MAXSwerveModule.java
Normal file
114
src/main/java/frc/robot/subsystems/MAXSwerveModule.java
Normal file
@ -0,0 +1,114 @@
|
|||||||
|
// Copyright (c) FIRST and other WPILib contributors.
|
||||||
|
// Open Source Software; you can modify and/or share it under the terms of
|
||||||
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
|
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||||
|
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||||
|
|
||||||
|
import com.revrobotics.spark.SparkClosedLoopController;
|
||||||
|
import com.revrobotics.spark.SparkMax;
|
||||||
|
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.revrobotics.AbsoluteEncoder;
|
||||||
|
import com.revrobotics.RelativeEncoder;
|
||||||
|
|
||||||
|
import frc.robot.Configs;
|
||||||
|
|
||||||
|
public class MAXSwerveModule {
|
||||||
|
private final SparkMax m_drivingSpark;
|
||||||
|
private final SparkMax m_turningSpark;
|
||||||
|
|
||||||
|
private final RelativeEncoder m_drivingEncoder;
|
||||||
|
private final AbsoluteEncoder m_turningEncoder;
|
||||||
|
|
||||||
|
private final SparkClosedLoopController m_drivingClosedLoopController;
|
||||||
|
private final SparkClosedLoopController m_turningClosedLoopController;
|
||||||
|
|
||||||
|
private double m_chassisAngularOffset = 0;
|
||||||
|
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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);
|
||||||
|
|
||||||
|
m_drivingEncoder = m_drivingSpark.getEncoder();
|
||||||
|
m_turningEncoder = m_turningSpark.getAbsoluteEncoder();
|
||||||
|
|
||||||
|
m_drivingClosedLoopController = m_drivingSpark.getClosedLoopController();
|
||||||
|
m_turningClosedLoopController = m_turningSpark.getClosedLoopController();
|
||||||
|
|
||||||
|
// 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(Configs.MAXSwerveModule.drivingConfig, ResetMode.kResetSafeParameters,
|
||||||
|
PersistMode.kPersistParameters);
|
||||||
|
m_turningSpark.configure(Configs.MAXSwerveModule.turningConfig, ResetMode.kResetSafeParameters,
|
||||||
|
PersistMode.kPersistParameters);
|
||||||
|
|
||||||
|
m_chassisAngularOffset = chassisAngularOffset;
|
||||||
|
m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
|
||||||
|
m_drivingEncoder.setPosition(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));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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));
|
||||||
|
|
||||||
|
// Optimize the reference state to avoid spinning further than 90 degrees.
|
||||||
|
correctedDesiredState.optimize(new Rotation2d(m_turningEncoder.getPosition()));
|
||||||
|
|
||||||
|
// Command driving and turning SPARKS towards their respective setpoints.
|
||||||
|
m_drivingClosedLoopController.setReference(correctedDesiredState.speedMetersPerSecond, ControlType.kVelocity);
|
||||||
|
m_turningClosedLoopController.setReference(correctedDesiredState.angle.getRadians(), ControlType.kPosition);
|
||||||
|
|
||||||
|
m_desiredState = desiredState;
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Zeroes all the SwerveModule encoders. */
|
||||||
|
public void resetEncoders() {
|
||||||
|
m_drivingEncoder.setPosition(0);
|
||||||
|
}
|
||||||
|
}
|
74
vendordeps/REVLib-2025.0.0-beta-2.json
Normal file
74
vendordeps/REVLib-2025.0.0-beta-2.json
Normal file
@ -0,0 +1,74 @@
|
|||||||
|
{
|
||||||
|
"fileName": "REVLib-2025.0.0-beta-2.json",
|
||||||
|
"name": "REVLib",
|
||||||
|
"version": "2025.0.0-beta-2",
|
||||||
|
"frcYear": "2025",
|
||||||
|
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
|
||||||
|
"mavenUrls": [
|
||||||
|
"https://maven.revrobotics.com/"
|
||||||
|
],
|
||||||
|
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json",
|
||||||
|
"javaDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "com.revrobotics.frc",
|
||||||
|
"artifactId": "REVLib-java",
|
||||||
|
"version": "2025.0.0-beta-2"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"jniDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "com.revrobotics.frc",
|
||||||
|
"artifactId": "REVLib-driver",
|
||||||
|
"version": "2025.0.0-beta-2",
|
||||||
|
"skipInvalidPlatforms": true,
|
||||||
|
"isJar": false,
|
||||||
|
"validPlatforms": [
|
||||||
|
"windowsx86-64",
|
||||||
|
"windowsx86",
|
||||||
|
"linuxarm64",
|
||||||
|
"linuxx86-64",
|
||||||
|
"linuxathena",
|
||||||
|
"linuxarm32",
|
||||||
|
"osxuniversal"
|
||||||
|
]
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"cppDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "com.revrobotics.frc",
|
||||||
|
"artifactId": "REVLib-cpp",
|
||||||
|
"version": "2025.0.0-beta-2",
|
||||||
|
"libName": "REVLib",
|
||||||
|
"headerClassifier": "headers",
|
||||||
|
"sharedLibrary": false,
|
||||||
|
"skipInvalidPlatforms": true,
|
||||||
|
"binaryPlatforms": [
|
||||||
|
"windowsx86-64",
|
||||||
|
"windowsx86",
|
||||||
|
"linuxarm64",
|
||||||
|
"linuxx86-64",
|
||||||
|
"linuxathena",
|
||||||
|
"linuxarm32",
|
||||||
|
"osxuniversal"
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"groupId": "com.revrobotics.frc",
|
||||||
|
"artifactId": "REVLib-driver",
|
||||||
|
"version": "2025.0.0-beta-2",
|
||||||
|
"libName": "REVLibDriver",
|
||||||
|
"headerClassifier": "headers",
|
||||||
|
"sharedLibrary": false,
|
||||||
|
"skipInvalidPlatforms": true,
|
||||||
|
"binaryPlatforms": [
|
||||||
|
"windowsx86-64",
|
||||||
|
"windowsx86",
|
||||||
|
"linuxarm64",
|
||||||
|
"linuxx86-64",
|
||||||
|
"linuxathena",
|
||||||
|
"linuxarm32",
|
||||||
|
"osxuniversal"
|
||||||
|
]
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
38
vendordeps/WPILibNewCommands.json
Normal file
38
vendordeps/WPILibNewCommands.json
Normal file
@ -0,0 +1,38 @@
|
|||||||
|
{
|
||||||
|
"fileName": "WPILibNewCommands.json",
|
||||||
|
"name": "WPILib-New-Commands",
|
||||||
|
"version": "1.0.0",
|
||||||
|
"uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266",
|
||||||
|
"frcYear": "2025",
|
||||||
|
"mavenUrls": [],
|
||||||
|
"jsonUrl": "",
|
||||||
|
"javaDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "edu.wpi.first.wpilibNewCommands",
|
||||||
|
"artifactId": "wpilibNewCommands-java",
|
||||||
|
"version": "wpilib"
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"jniDependencies": [],
|
||||||
|
"cppDependencies": [
|
||||||
|
{
|
||||||
|
"groupId": "edu.wpi.first.wpilibNewCommands",
|
||||||
|
"artifactId": "wpilibNewCommands-cpp",
|
||||||
|
"version": "wpilib",
|
||||||
|
"libName": "wpilibNewCommands",
|
||||||
|
"headerClassifier": "headers",
|
||||||
|
"sourcesClassifier": "sources",
|
||||||
|
"sharedLibrary": true,
|
||||||
|
"skipInvalidPlatforms": true,
|
||||||
|
"binaryPlatforms": [
|
||||||
|
"linuxathena",
|
||||||
|
"linuxarm32",
|
||||||
|
"linuxarm64",
|
||||||
|
"windowsx86-64",
|
||||||
|
"windowsx86",
|
||||||
|
"linuxx86-64",
|
||||||
|
"osxuniversal"
|
||||||
|
]
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
Loading…
Reference in New Issue
Block a user