├── .github
└── workflows
│ └── gradle.yml
├── .gitignore
├── LICENSE
├── README.md
├── SpikesLib2.json
├── build.gradle
├── docs
├── README.md
└── _config.yml
├── gradle
└── wrapper
│ ├── gradle-wrapper.jar
│ └── gradle-wrapper.properties
├── gradlew
├── gradlew.bat
├── jitpack.yml
├── settings.gradle
└── src
└── main
└── java
└── com
└── spikes2212
├── command
├── DashboardedSubsystem.java
├── DoubleSolenoidSubsystem.java
├── drivetrains
│ ├── OdometryDrivetrain.java
│ ├── TankDrivetrain.java
│ ├── commands
│ │ ├── DriveArcade.java
│ │ ├── DriveArcadeWithPID.java
│ │ ├── DriveArcadeWithVoltages.java
│ │ ├── DriveCurvature.java
│ │ ├── DriveTank.java
│ │ ├── DriveTankWithPID.java
│ │ ├── DriveTankWithVoltages.java
│ │ ├── FollowPath.java
│ │ ├── OrientWithPID.java
│ │ └── smartmotorcontrollerdrivetrain
│ │ │ ├── MoveSmartMotorControllerTankDrivetrain.java
│ │ │ └── MoveSmartMotorControllerTankDrivetrainTrapezically.java
│ └── smartmotorcontrollerdrivetrain
│ │ ├── SmartMotorControllerTankDrivetrain.java
│ │ ├── SparkTankDrivetrain.java
│ │ └── TalonFXTankDrivetrain.java
└── genericsubsystem
│ ├── GenericSubsystem.java
│ ├── MotoredGenericSubsystem.java
│ ├── commands
│ ├── AccelerateGenericSubsystem.java
│ ├── MoveGenericSubsystem.java
│ ├── MoveGenericSubsystemWithPID.java
│ ├── MoveGenericSubsystemWithPIDForSpeed.java
│ └── smartmotorcontrollergenericsubsystem
│ │ ├── MoveSmartMotorControllerGenericSubsystem.java
│ │ └── MoveSmartMotorControllerSubsystemTrapezically.java
│ └── smartmotorcontrollersubsystem
│ ├── SmartMotorControllerGenericSubsystem.java
│ ├── SparkGenericSubsystem.java
│ └── TalonFXGenericSubsystem.java
├── control
├── FeedForwardController.java
├── FeedForwardSettings.java
├── PIDSettings.java
├── TrapezoidProfileSettings.java
└── noise
│ ├── ExponentialFilter.java
│ ├── NoiseFilter.java
│ ├── NoiseReducer.java
│ └── RunningAverageFilter.java
├── dashboard
├── AutoChooser.java
├── ChildNamespace.java
├── Namespace.java
├── RootNamespace.java
└── SpikesLogger.java
├── path
├── OdometryHandler.java
├── Paths.java
├── PurePursuitController.java
├── README.md
├── RateLimiter.java
└── Waypoint.java
├── state
├── ButtonLayout.java
├── LayoutManager.java
└── StateMachine.java
└── util
├── AddressableLEDWrapper.java
├── BustedMotorControllerGroup.java
├── DPAD.java
├── Limelight.java
├── MotorControllerGroup.java
├── PigeonWrapper.java
├── PlaystationControllerWrapper.java
├── TalonEncoder.java
├── UnifiedControlMode.java
├── XboxControllerWrapper.java
└── smartmotorcontrollers
├── SmartMotorController.java
├── SparkWrapper.java
└── TalonFXWrapper.java
/.github/workflows/gradle.yml:
--------------------------------------------------------------------------------
1 | name: Java CI with Gradle
2 |
3 | on: [ push,pull_request ]
4 |
5 | jobs:
6 | build:
7 |
8 | runs-on: ubuntu-latest
9 |
10 | steps:
11 | - uses: actions/checkout@v2
12 | - name: Set up JDK 17
13 | uses: actions/setup-java@v2
14 | with:
15 | java-version: '17'
16 | distribution: 'adopt'
17 | - name: Grant execute permission for gradlew
18 | run: chmod +x gradlew
19 | - name: Build with Gradle
20 | run: ./gradlew build --scan
21 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # Ignore Gradle project-specific cache directory
2 | .gradle
3 |
4 | # Ignore Gradle build output directory
5 | build
6 |
7 | .idea
8 |
9 | bin
10 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2020 Spikes #2212
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 |
2 | SpikesLib
3 | SpikesLib is a library that extends WPILib written by the FRC team The
4 | Spikes#2212.
5 |
6 | Examples
7 | Examples of how to use the library can be
8 | found here.
9 |
10 | Packages
11 |
12 | command - extensions for WPILib's Command Based framework
13 | control - controller wrappers and custom controllers
14 | dashboard - wrappers for NetworkTables elements
15 | path - path following code and pure pursuit algorithm
16 | util - additional utilities
17 |
18 | Installation
19 | After creating a Robot Project, import SpikesLib as an online vendor libray, using this link:
20 | https://spikes2212.com/SpikesLib.json
21 |
22 | 2025 Season
23 |
24 | SpikesLib has been updated to support WPILib 2025.
25 |
26 | 2024 Season
27 |
28 | SpikesLib has been
29 | updated to support WPILib 2024.
30 |
31 | 2023 Season
32 |
33 | SpikesLib has been
34 | updated to support WPILib 2023.
35 |
36 | 2022 Season
37 |
38 | SpikesLib has been updated to support WPILib 2022.
39 |
40 | 2020 Season
41 |
42 | For this season, SpikesLib has been moved to this repository due to the extensive changes in WPILib.
43 | The old version is still available at the [old repository](https://github.com/Spikes-2212-Programming-Guild/SpikesLib).
44 |
45 | Development
46 | SpikesLib is developed in a feature branches workflow.
47 | All feature branches are merged into dev
branch after testing, which in turn is merged into
48 | master
after it passing complete testing
49 | Branches should be named according to the following convention - name_package_feature
50 |
51 | Help us out!
52 | We accept help from everyone!
53 | If you want to contribute, simply create a branch and open up a pull request, according to the instructions above.
54 |
55 |
56 |
--------------------------------------------------------------------------------
/SpikesLib2.json:
--------------------------------------------------------------------------------
1 | {
2 | "fileName": "SpikesLib2.json",
3 | "name": "SpikesLib2",
4 | "version": "v5.1.1",
5 | "frcYear": "2025",
6 | "uuid": "018a8f54-8662-11ec-a8a3-0242ac120002",
7 | "jsonUrl": "https://raw.githubusercontent.com/Spikes-2212-Programming-Guild/SpikesLib2/master/SpikesLib2.json",
8 | "mavenUrls": [
9 | "https://jitpack.io"
10 | ],
11 | "jniDependencies": [],
12 | "cppDependencies": [
13 | ],
14 | "javaDependencies": [
15 | {
16 | "groupId": "com.github.Spikes-2212-Programming-Guild",
17 | "artifactId": "SpikesLib2",
18 | "version": "v5.1.1"
19 | }
20 | ]
21 | }
22 |
--------------------------------------------------------------------------------
/build.gradle:
--------------------------------------------------------------------------------
1 | plugins {
2 | id 'java-library'
3 | id 'maven-publish'
4 | id 'net.researchgate.release' version '2.6.0'
5 | }
6 |
7 | sourceCompatibility = JavaVersion.VERSION_17
8 | targetCompatibility = JavaVersion.VERSION_17
9 |
10 | group = 'com.github.Spikes-2212-Programming-Guild'
11 |
12 | repositories {
13 | mavenCentral()
14 | maven {
15 | url 'https://maven.ctr-electronics.com/release/'
16 | }
17 | maven {
18 | url 'https://frcmaven.wpi.edu/artifactory/release'
19 | }
20 | maven {
21 | url 'https://maven.revrobotics.com'
22 | }
23 | maven {
24 | url 'https://jitpack.io'
25 | }
26 | }
27 |
28 | publishing {
29 | publications {
30 | mavenJava(MavenPublication) {
31 | groupId = 'org.gradle.sample'
32 | artifactId = 'library'
33 | version = '5.1.1'
34 |
35 | from components.java
36 | }
37 | }
38 | }
39 |
40 | dependencies {
41 | implementation group: 'com.ctre.phoenix6', name: 'wpiapi-java', version: '25.2.1'
42 | implementation group: 'edu.wpi.first.ntcore', name: 'ntcore-java', version: '2025.1.1'
43 | implementation group: 'edu.wpi.first.wpilibNewCommands', name: 'wpilibNewCommands-java', version: '2025.1.1'
44 | implementation group: 'edu.wpi.first.wpilibj', name: 'wpilibj-java', version: '2025.1.1'
45 | implementation group: 'edu.wpi.first.cameraserver', name: 'cameraserver-java', version: '2025.1.1'
46 | implementation group: 'edu.wpi.first.wpiutil', name: 'wpiutil-java', version: '2025.1.1'
47 | implementation group: 'edu.wpi.first.wpimath', name: 'wpimath-java', version: '2025.1.1'
48 | implementation group: 'edu.wpi.first.wpiunits', name: 'wpiunits-java', version: '2025.1.1'
49 | implementation group: 'com.revrobotics.frc', name: 'REVLib-java', version: '2025.0.2'
50 | implementation group: 'com.ctre.phoenix', name: 'api-java', version: '5.35.1'
51 | implementation group: 'com.ctre.phoenix', name: 'wpiapi-java', version: '5.35.1'
52 | }
53 |
--------------------------------------------------------------------------------
/docs/README.md:
--------------------------------------------------------------------------------
1 |
2 | SpikesLib is a library that extends
WPILib written by the FRC team The
3 | Spikes#2212.
4 |
5 |
6 |
Packages
7 |
8 |
command - extensions for WPILib's Command Based framework
9 |
control - controller wrappers and custom controllers
10 |
dashboard - wrappers for NetworkTables elements
11 |
path - path following code and pure pursuit algorithm
12 |
util - additional utilities
13 |
14 |
Installation
15 | After creating a Robot Project, import SpikesLib as an online vendor libray, using this link:
16 | https://spikes2212.com/SpikesLib.json
17 |
18 |
2025 Season
19 |
20 | SpikesLib has been
updated to support WPILib 2025.
21 |
22 |
2024 Season
23 |
24 | SpikesLib has been
updated to support WPILib 2024.
25 |
26 |
2023 Season
27 |
28 | SpikesLib has been
updated to support WPILib 2023.
29 |
30 |
2022 Season
31 |
32 | SpikesLib has been updated to support WPILib 2022.
33 |
34 |
2020 Season
35 |
36 | For this season, SpikesLib has been moved to this repository due to the extensive changes in WPILib.
37 | The old version is still available at the
old repository.
39 |
40 |
Development
41 | SpikesLib is developed in a feature branches workflow.
42 | All feature branches are merged into
dev
branch after testing, which in turn is merged into
43 |
master
after it passing complete testing
44 | Branches should be named according to the following convention -
name_package_feature
45 |
46 |
Help us out!
47 | We accept help from everyone!
48 | If you want to contribute, simply create a branch and open up a pull request, according to the instructions above.
49 |
50 |
51 |
--------------------------------------------------------------------------------
/docs/_config.yml:
--------------------------------------------------------------------------------
1 | title:
2 | SpikesLib
3 | description: a Spikes#2212 library
4 |
--------------------------------------------------------------------------------
/gradle/wrapper/gradle-wrapper.jar:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/Spikes-2212-Programming-Guild/SpikesLib2/2471c29a949f381235f5c33c6c03bdcf8613c6ab/gradle/wrapper/gradle-wrapper.jar
--------------------------------------------------------------------------------
/gradle/wrapper/gradle-wrapper.properties:
--------------------------------------------------------------------------------
1 | distributionBase=GRADLE_USER_HOME
2 | distributionPath=wrapper/dists
3 | distributionUrl=https\://services.gradle.org/distributions/gradle-7.4.2-bin.zip
4 | zipStoreBase=GRADLE_USER_HOME
5 | zipStorePath=wrapper/dists
6 |
--------------------------------------------------------------------------------
/gradlew:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 |
3 | #
4 | # Copyright © 2015-2021 the original authors.
5 | #
6 | # Licensed under the Apache License, Version 2.0 (the "License");
7 | # you may not use this file except in compliance with the License.
8 | # You may obtain a copy of the License at
9 | #
10 | # https://www.apache.org/licenses/LICENSE-2.0
11 | #
12 | # Unless required by applicable law or agreed to in writing, software
13 | # distributed under the License is distributed on an "AS IS" BASIS,
14 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 | # See the License for the specific language governing permissions and
16 | # limitations under the License.
17 | #
18 |
19 | ##############################################################################
20 | #
21 | # Gradle start up script for POSIX generated by Gradle.
22 | #
23 | # Important for running:
24 | #
25 | # (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is
26 | # noncompliant, but you have some other compliant shell such as ksh or
27 | # bash, then to run this script, type that shell name before the whole
28 | # command line, like:
29 | #
30 | # ksh Gradle
31 | #
32 | # Busybox and similar reduced shells will NOT work, because this script
33 | # requires all of these POSIX shell features:
34 | # * functions;
35 | # * expansions «$var», «${var}», «${var:-default}», «${var+SET}»,
36 | # «${var#prefix}», «${var%suffix}», and «$( cmd )»;
37 | # * compound commands having a testable exit status, especially «case»;
38 | # * various built-in commands including «command», «set», and «ulimit».
39 | #
40 | # Important for patching:
41 | #
42 | # (2) This script targets any POSIX shell, so it avoids extensions provided
43 | # by Bash, Ksh, etc; in particular arrays are avoided.
44 | #
45 | # The "traditional" practice of packing multiple parameters into a
46 | # space-separated string is a well documented source of bugs and security
47 | # problems, so this is (mostly) avoided, by progressively accumulating
48 | # options in "$@", and eventually passing that to Java.
49 | #
50 | # Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS,
51 | # and GRADLE_OPTS) rely on word-splitting, this is performed explicitly;
52 | # see the in-line comments for details.
53 | #
54 | # There are tweaks for specific operating systems such as AIX, CygWin,
55 | # Darwin, MinGW, and NonStop.
56 | #
57 | # (3) This script is generated from the Groovy template
58 | # https://github.com/gradle/gradle/blob/master/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt
59 | # within the Gradle project.
60 | #
61 | # You can find Gradle at https://github.com/gradle/gradle/.
62 | #
63 | ##############################################################################
64 |
65 | # Attempt to set APP_HOME
66 |
67 | # Resolve links: $0 may be a link
68 | app_path=$0
69 |
70 | # Need this for daisy-chained symlinks.
71 | while
72 | APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path
73 | [ -h "$app_path" ]
74 | do
75 | ls=$( ls -ld "$app_path" )
76 | link=${ls#*' -> '}
77 | case $link in #(
78 | /*) app_path=$link ;; #(
79 | *) app_path=$APP_HOME$link ;;
80 | esac
81 | done
82 |
83 | APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit
84 |
85 | APP_NAME="Gradle"
86 | APP_BASE_NAME=${0##*/}
87 |
88 | # Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script.
89 | DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"'
90 |
91 | # Use the maximum available, or set MAX_FD != -1 to use that value.
92 | MAX_FD=maximum
93 |
94 | warn () {
95 | echo "$*"
96 | } >&2
97 |
98 | die () {
99 | echo
100 | echo "$*"
101 | echo
102 | exit 1
103 | } >&2
104 |
105 | # OS specific support (must be 'true' or 'false').
106 | cygwin=false
107 | msys=false
108 | darwin=false
109 | nonstop=false
110 | case "$( uname )" in #(
111 | CYGWIN* ) cygwin=true ;; #(
112 | Darwin* ) darwin=true ;; #(
113 | MSYS* | MINGW* ) msys=true ;; #(
114 | NONSTOP* ) nonstop=true ;;
115 | esac
116 |
117 | CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar
118 |
119 |
120 | # Determine the Java command to use to start the JVM.
121 | if [ -n "$JAVA_HOME" ] ; then
122 | if [ -x "$JAVA_HOME/jre/sh/java" ] ; then
123 | # IBM's JDK on AIX uses strange locations for the executables
124 | JAVACMD=$JAVA_HOME/jre/sh/java
125 | else
126 | JAVACMD=$JAVA_HOME/bin/java
127 | fi
128 | if [ ! -x "$JAVACMD" ] ; then
129 | die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME
130 |
131 | Please set the JAVA_HOME variable in your environment to match the
132 | location of your Java installation."
133 | fi
134 | else
135 | JAVACMD=java
136 | which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
137 |
138 | Please set the JAVA_HOME variable in your environment to match the
139 | location of your Java installation."
140 | fi
141 |
142 | # Increase the maximum file descriptors if we can.
143 | if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then
144 | case $MAX_FD in #(
145 | max*)
146 | MAX_FD=$( ulimit -H -n ) ||
147 | warn "Could not query maximum file descriptor limit"
148 | esac
149 | case $MAX_FD in #(
150 | '' | soft) :;; #(
151 | *)
152 | ulimit -n "$MAX_FD" ||
153 | warn "Could not set maximum file descriptor limit to $MAX_FD"
154 | esac
155 | fi
156 |
157 | # Collect all arguments for the java command, stacking in reverse order:
158 | # * args from the command line
159 | # * the main class name
160 | # * -classpath
161 | # * -D...appname settings
162 | # * --module-path (only if needed)
163 | # * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables.
164 |
165 | # For Cygwin or MSYS, switch paths to Windows format before running java
166 | if "$cygwin" || "$msys" ; then
167 | APP_HOME=$( cygpath --path --mixed "$APP_HOME" )
168 | CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" )
169 |
170 | JAVACMD=$( cygpath --unix "$JAVACMD" )
171 |
172 | # Now convert the arguments - kludge to limit ourselves to /bin/sh
173 | for arg do
174 | if
175 | case $arg in #(
176 | -*) false ;; # don't mess with options #(
177 | /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath
178 | [ -e "$t" ] ;; #(
179 | *) false ;;
180 | esac
181 | then
182 | arg=$( cygpath --path --ignore --mixed "$arg" )
183 | fi
184 | # Roll the args list around exactly as many times as the number of
185 | # args, so each arg winds up back in the position where it started, but
186 | # possibly modified.
187 | #
188 | # NB: a `for` loop captures its iteration list before it begins, so
189 | # changing the positional parameters here affects neither the number of
190 | # iterations, nor the values presented in `arg`.
191 | shift # remove old arg
192 | set -- "$@" "$arg" # push replacement arg
193 | done
194 | fi
195 |
196 | # Collect all arguments for the java command;
197 | # * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of
198 | # shell script including quotes and variable substitutions, so put them in
199 | # double quotes to make sure that they get re-expanded; and
200 | # * put everything else in single quotes, so that it's not re-expanded.
201 |
202 | set -- \
203 | "-Dorg.gradle.appname=$APP_BASE_NAME" \
204 | -classpath "$CLASSPATH" \
205 | org.gradle.wrapper.GradleWrapperMain \
206 | "$@"
207 |
208 | # Use "xargs" to parse quoted args.
209 | #
210 | # With -n1 it outputs one arg per line, with the quotes and backslashes removed.
211 | #
212 | # In Bash we could simply go:
213 | #
214 | # readarray ARGS < <( xargs -n1 <<<"$var" ) &&
215 | # set -- "${ARGS[@]}" "$@"
216 | #
217 | # but POSIX shell has neither arrays nor command substitution, so instead we
218 | # post-process each arg (as a line of input to sed) to backslash-escape any
219 | # character that might be a shell metacharacter, then use eval to reverse
220 | # that process (while maintaining the separation between arguments), and wrap
221 | # the whole thing up as a single "set" statement.
222 | #
223 | # This will of course break if any of these variables contains a newline or
224 | # an unmatched quote.
225 | #
226 |
227 | eval "set -- $(
228 | printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" |
229 | xargs -n1 |
230 | sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' |
231 | tr '\n' ' '
232 | )" '"$@"'
233 |
234 | exec "$JAVACMD" "$@"
235 |
--------------------------------------------------------------------------------
/gradlew.bat:
--------------------------------------------------------------------------------
1 | @rem
2 | @rem Copyright 2015 the original author or authors.
3 | @rem
4 | @rem Licensed under the Apache License, Version 2.0 (the "License");
5 | @rem you may not use this file except in compliance with the License.
6 | @rem You may obtain a copy of the License at
7 | @rem
8 | @rem https://www.apache.org/licenses/LICENSE-2.0
9 | @rem
10 | @rem Unless required by applicable law or agreed to in writing, software
11 | @rem distributed under the License is distributed on an "AS IS" BASIS,
12 | @rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | @rem See the License for the specific language governing permissions and
14 | @rem limitations under the License.
15 | @rem
16 |
17 | @if "%DEBUG%" == "" @echo off
18 | @rem ##########################################################################
19 | @rem
20 | @rem Gradle startup script for Windows
21 | @rem
22 | @rem ##########################################################################
23 |
24 | @rem Set local scope for the variables with windows NT shell
25 | if "%OS%"=="Windows_NT" setlocal
26 |
27 | set DIRNAME=%~dp0
28 | if "%DIRNAME%" == "" set DIRNAME=.
29 | set APP_BASE_NAME=%~n0
30 | set APP_HOME=%DIRNAME%
31 |
32 | @rem Resolve any "." and ".." in APP_HOME to make it shorter.
33 | for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi
34 |
35 | @rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script.
36 | set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m"
37 |
38 | @rem Find java.exe
39 | if defined JAVA_HOME goto findJavaFromJavaHome
40 |
41 | set JAVA_EXE=java.exe
42 | %JAVA_EXE% -version >NUL 2>&1
43 | if "%ERRORLEVEL%" == "0" goto execute
44 |
45 | echo.
46 | echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
47 | echo.
48 | echo Please set the JAVA_HOME variable in your environment to match the
49 | echo location of your Java installation.
50 |
51 | goto fail
52 |
53 | :findJavaFromJavaHome
54 | set JAVA_HOME=%JAVA_HOME:"=%
55 | set JAVA_EXE=%JAVA_HOME%/bin/java.exe
56 |
57 | if exist "%JAVA_EXE%" goto execute
58 |
59 | echo.
60 | echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME%
61 | echo.
62 | echo Please set the JAVA_HOME variable in your environment to match the
63 | echo location of your Java installation.
64 |
65 | goto fail
66 |
67 | :execute
68 | @rem Setup the command line
69 |
70 | set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar
71 |
72 |
73 | @rem Execute Gradle
74 | "%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %*
75 |
76 | :end
77 | @rem End local scope for the variables with windows NT shell
78 | if "%ERRORLEVEL%"=="0" goto mainEnd
79 |
80 | :fail
81 | rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of
82 | rem the _cmd.exe /c_ return code!
83 | if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1
84 | exit /b 1
85 |
86 | :mainEnd
87 | if "%OS%"=="Windows_NT" endlocal
88 |
89 | :omega
90 |
--------------------------------------------------------------------------------
/jitpack.yml:
--------------------------------------------------------------------------------
1 | jdk:
2 | -openjdk17
3 |
--------------------------------------------------------------------------------
/settings.gradle:
--------------------------------------------------------------------------------
1 | /*
2 | * This file was generated by the Gradle 'init' task.
3 | *
4 | * The settings file is used to specify which projects to include in your build.
5 | *
6 | * Detailed information about configuring a multi-project build in Gradle can be found
7 | * in the user manual at https://docs.gradle.org/5.6.4/userguide/multi_project_builds.html
8 | */
9 |
10 | rootProject.name = 'spikeslib-v2'
11 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/DashboardedSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command;
2 |
3 | import com.spikes2212.dashboard.Namespace;
4 | import com.spikes2212.dashboard.RootNamespace;
5 | import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
6 | import edu.wpi.first.wpilibj2.command.Subsystem;
7 | import edu.wpi.first.wpilibj2.command.SubsystemBase;
8 |
9 | import java.util.Arrays;
10 | import java.util.Collections;
11 | import java.util.List;
12 |
13 | /**
14 | * A {@link Subsystem} that includes a {@link Namespace}, which lets you see and configure data using the
15 | * {@link SmartDashboard}.
16 | *
17 | * @author Yoel Perman Brilliant
18 | */
19 | public abstract class DashboardedSubsystem extends SubsystemBase {
20 |
21 | protected final Namespace namespace;
22 |
23 | public DashboardedSubsystem(Namespace namespace) {
24 | this.namespace = namespace;
25 | }
26 |
27 | public DashboardedSubsystem(String namespaceName) {
28 | this(new RootNamespace(namespaceName));
29 | }
30 |
31 | /**
32 | * Updates the {@link Namespace}. Should be called in the {@code robotPeriodic()} method in {@code Robot}.
33 | */
34 | @Override
35 | public void periodic() {
36 | namespace.update();
37 | }
38 |
39 | public abstract void configureDashboard();
40 |
41 | /**
42 | * Should be used inside a constructor to get the name of the class of the object that is being created.
43 | * The method achieves that by finding the earliest constructor in the method call stack.
44 | *
45 | * @param defaultName default return value in case the method, for any reason, does not find a constructor.
46 | * @return name of the class
47 | */
48 | protected static String getClassName(String defaultName) {
49 | List elements = Arrays.asList(Thread.currentThread().getStackTrace());
50 | Collections.reverse(elements);
51 | for (StackTraceElement element : elements) {
52 | if (element.toString().contains("."))
53 | return element.getClassName();
54 | }
55 | return defaultName;
56 | }
57 | }
58 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/DoubleSolenoidSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command;
2 |
3 | import com.spikes2212.dashboard.Namespace;
4 | import com.spikes2212.dashboard.RootNamespace;
5 | import edu.wpi.first.networktables.NetworkTable;
6 | import edu.wpi.first.wpilibj.DoubleSolenoid;
7 | import edu.wpi.first.wpilibj2.command.InstantCommand;
8 | import edu.wpi.first.wpilibj2.command.Subsystem;
9 |
10 | /**
11 | * A {@link Subsystem} that controls a double solenoid.
12 | *
13 | * @author Camellia Lami
14 | * @see DashboardedSubsystem
15 | */
16 | public class DoubleSolenoidSubsystem extends DashboardedSubsystem {
17 |
18 | private final DoubleSolenoid doubleSolenoid;
19 | private final boolean inverted;
20 |
21 | public DoubleSolenoidSubsystem(Namespace namespace, DoubleSolenoid doubleSolenoid, boolean inverted) {
22 | super(namespace);
23 | this.doubleSolenoid = doubleSolenoid;
24 | this.inverted = inverted;
25 | }
26 |
27 | public DoubleSolenoidSubsystem(String namespaceName, DoubleSolenoid doubleSolenoid, boolean inverted) {
28 | this(new RootNamespace(namespaceName), doubleSolenoid, inverted);
29 | }
30 |
31 | /**
32 | * Opens the double solenoid.
33 | *
34 | * @return an {@link InstantCommand} that opens the solenoid
35 | */
36 | public InstantCommand openCommand() {
37 | if (inverted) {
38 | return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kForward), this);
39 | }
40 | return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kReverse), this);
41 | }
42 |
43 | /**
44 | * Closes the double solenoid.
45 | *
46 | * @return an {@link InstantCommand} that closes the solenoid
47 | */
48 | public InstantCommand closeCommand() {
49 | if (inverted) {
50 | return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kReverse), this);
51 | }
52 | return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kForward), this);
53 | }
54 |
55 | /**
56 | * Adds any commands or data from this subsystem to the {@link NetworkTable}s.
57 | */
58 | @Override
59 | public void configureDashboard() {
60 | }
61 | }
62 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/OdometryDrivetrain.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains;
2 |
3 | import com.spikes2212.path.OdometryHandler;
4 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
5 |
6 | @Deprecated(forRemoval = true, since = "2025")
7 | public abstract class OdometryDrivetrain extends TankDrivetrain {
8 |
9 | public OdometryDrivetrain(String namespaceName, MotorController left, MotorController right) {
10 | super(namespaceName, left, right);
11 | }
12 |
13 | public abstract OdometryHandler getHandler();
14 |
15 | public abstract double getWidth();
16 |
17 | public abstract void zeroSensors();
18 |
19 | public abstract double getLeftRate();
20 |
21 | public abstract double getRightRate();
22 |
23 | public abstract void setInverted(boolean inverted);
24 |
25 | @Override
26 | public void periodic() {
27 | getHandler().calculate();
28 | super.periodic();
29 | }
30 | }
31 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/TankDrivetrain.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains;
2 |
3 | import com.spikes2212.command.DashboardedSubsystem;
4 | import com.spikes2212.util.MotorControllerGroup;
5 | import edu.wpi.first.networktables.NetworkTable;
6 | import edu.wpi.first.wpilibj.RobotController;
7 | import edu.wpi.first.wpilibj.drive.DifferentialDrive;
8 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
9 |
10 | /**
11 | * This class represents a type of drivetrain that its left and right sides are controlled independently,
12 | * allowing it to move by giving each side a speed value separately.
13 | *
14 | * It can move forwards/backwards by giving both its sides an equal speed or
15 | * turn by giving the sides different speeds.
16 | *
17 | * @author Yuval Levy
18 | * @see DashboardedSubsystem
19 | */
20 | public class TankDrivetrain extends DashboardedSubsystem {
21 |
22 | private static final String DEFAULT_NAMESPACE_NAME = "tank drivetrain";
23 |
24 | protected final MotorController leftController;
25 | protected final MotorController rightController;
26 |
27 | private final DifferentialDrive drive;
28 |
29 | public TankDrivetrain(String namespaceName, MotorController leftController, MotorController rightController) {
30 | super(namespaceName);
31 | this.leftController = leftController;
32 | this.rightController = rightController;
33 | rightController.setInverted(true);
34 | drive = new DifferentialDrive(leftController, rightController);
35 | drive.setSafetyEnabled(false);
36 | }
37 |
38 | public TankDrivetrain(MotorController leftController, MotorController rightController) {
39 | this(getClassName(DEFAULT_NAMESPACE_NAME), leftController, rightController);
40 | }
41 |
42 | public TankDrivetrain(String namespaceName, MotorController leftMaster, MotorController leftSlave,
43 | MotorController rightMaster, MotorController rightSlave) {
44 | this(namespaceName, new MotorControllerGroup(leftMaster, leftSlave),
45 | new MotorControllerGroup(rightMaster, rightSlave));
46 | }
47 |
48 | public TankDrivetrain(MotorController leftMaster, MotorController leftSlave,
49 | MotorController rightMaster, MotorController rightSlave) {
50 | this(new MotorControllerGroup(leftMaster, leftSlave),
51 | new MotorControllerGroup(rightMaster, rightSlave));
52 | }
53 |
54 | /**
55 | * Moves both sides of this drivetrain by the given speeds for each side.
56 | *
57 | * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
58 | * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward
59 | */
60 | public void tankDrive(double leftSpeed, double rightSpeed) {
61 | drive.tankDrive(leftSpeed, rightSpeed, false);
62 | }
63 |
64 | /**
65 | * Moves both sides of this drivetrain by the given speeds for each side.
66 | *
67 | * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
68 | * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward
69 | * @param squareInputs whether to square the given inputs before putting them in the speed controllers
70 | */
71 | public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) {
72 | drive.tankDrive(leftSpeed, rightSpeed, squareInputs);
73 | }
74 |
75 | /**
76 | * Moves both sides of this drivetrain by the given voltages for each side.
77 | *
78 | * @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward
79 | * @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward
80 | */
81 | public void tankDriveVoltages(double leftVoltage, double rightVoltage) {
82 | tankDrive(leftVoltage / RobotController.getBatteryVoltage(),
83 | rightVoltage / RobotController.getBatteryVoltage(), false);
84 | }
85 |
86 | /**
87 | * Moves the drivetrain by the given forward and angular speed.
88 | *
89 | * @param moveValue the forward movement speed (-1 to 1)
90 | * @param rotateValue the angular movement speed (-1 to 1). Positive values go clockwise
91 | */
92 | public void arcadeDrive(double moveValue, double rotateValue) {
93 | drive.arcadeDrive(moveValue, rotateValue, false);
94 | }
95 |
96 | /**
97 | * Moves the drivetrain by the given forward and angular speed.
98 | *
99 | * @param moveValue the forward movement speed (-1 to 1)
100 | * @param rotateValue the angular movement speed (-1 to 1). Positive values go clockwise
101 | * @param squareInputs whether to square the given inputs before putting them in the speed controllers
102 | */
103 | public void arcadeDrive(double moveValue, double rotateValue, boolean squareInputs) {
104 | drive.arcadeDrive(moveValue, rotateValue, squareInputs);
105 | }
106 |
107 | /**
108 | * Moves the drivetrain by the given forward and angular voltage.
109 | *
110 | * @param moveVoltage the forward movement voltage (-12 to 12)
111 | * @param rotateVoltage the angular movement voltage (-12 to 12). Positive values go clockwise
112 | */
113 | public void arcadeDriveVoltages(double moveVoltage, double rotateVoltage) {
114 | arcadeDrive(moveVoltage / RobotController.getBatteryVoltage(),
115 | rotateVoltage / RobotController.getBatteryVoltage(), false);
116 | }
117 |
118 | /**
119 | * Moves the drivetrain while rotating it at a given curvature.
120 | *
121 | * @param speed the forward movement speed (-1 to 1)
122 | * @param curvature the curvature of the robot's path (-1 to 1). Positive values go clockwise
123 | */
124 | public void curvatureDrive(double speed, double curvature) {
125 | drive.curvatureDrive(speed, curvature, true);
126 | }
127 |
128 | /**
129 | * Moves the left side of this drivetrain by a given speed.
130 | *
131 | * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
132 | */
133 | public void setLeft(double leftSpeed) {
134 | leftController.set(leftSpeed);
135 | }
136 |
137 | /**
138 | * Moves the right side of this drivetrain by a given speed.
139 | *
140 | * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward
141 | */
142 | public void setRight(double rightSpeed) {
143 | rightController.set(rightSpeed);
144 | }
145 |
146 | /**
147 | * Moves the left side of this drivetrain by a given voltage.
148 | *
149 | * @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward
150 | */
151 | public void setLeftVoltage(double leftVoltage) {
152 | setLeft(leftVoltage / RobotController.getBatteryVoltage());
153 | }
154 |
155 | /**
156 | * Moves the right side of this drivetrain by a given voltage.
157 | *
158 | * @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward
159 | */
160 | public void setRightVoltage(double rightVoltage) {
161 | setRight(rightVoltage / RobotController.getBatteryVoltage());
162 | }
163 |
164 | /**
165 | * Stops the drivetrain.
166 | */
167 | public void stop() {
168 | leftController.stopMotor();
169 | rightController.stopMotor();
170 | }
171 |
172 | /**
173 | * Sets the motor safety feature of the speed controllers on/off.
174 | *
175 | * @param enabled whether motor safety should be enabled
176 | */
177 | public void setMotorSafety(boolean enabled) {
178 | drive.setSafetyEnabled(enabled);
179 | }
180 |
181 | /**
182 | * Adds any commands or data from this subsystem to the {@link NetworkTable}s.
183 | */
184 | @Override
185 | public void configureDashboard() {
186 | }
187 | }
188 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveArcade.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * A command that moves a {@link TankDrivetrain} using linear and rotational speeds.
10 | *
11 | * @author Yuval Levy
12 | * @see TankDrivetrain
13 | */
14 |
15 | public class DriveArcade extends Command {
16 |
17 | protected final TankDrivetrain tankDrivetrain;
18 | protected final Supplier moveValueSupplier;
19 | protected final Supplier rotateValueSupplier;
20 | protected final Supplier isFinished;
21 |
22 | /**
23 | * Whether to square the velocity suppliers.
24 | */
25 | protected final boolean squareInputs;
26 |
27 | /**
28 | * Constructs a new {@link DriveArcade} command that moves the given
29 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
30 | * for linear and rotational movements.
31 | *
32 | * @param drivetrain the tank drivetrain this command operates on
33 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
34 | * Positive values go forwards
35 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
36 | * Positive values go clockwise
37 | * @param isFinished when to finish the command
38 | * @param squareInputs whether to square the speed suppliers' values
39 | */
40 | public DriveArcade(TankDrivetrain drivetrain, Supplier moveValueSupplier,
41 | Supplier rotateValueSupplier, Supplier isFinished, boolean squareInputs) {
42 | addRequirements(drivetrain);
43 | this.tankDrivetrain = drivetrain;
44 | this.moveValueSupplier = moveValueSupplier;
45 | this.rotateValueSupplier = rotateValueSupplier;
46 | this.isFinished = isFinished;
47 | this.squareInputs = squareInputs;
48 | }
49 |
50 | /**
51 | * Constructs a new {@link DriveArcade} command that moves the given
52 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
53 | * for linear and rotational movements. Does not square the inputs.
54 | *
55 | * @param drivetrain the tank drivetrain this command operates on
56 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
57 | * Positive values go forwards
58 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
59 | * Positive values go clockwise
60 | * @param isFinished when to finish the command
61 | */
62 | public DriveArcade(TankDrivetrain drivetrain, Supplier moveValueSupplier,
63 | Supplier rotateValueSupplier, Supplier isFinished) {
64 | this(drivetrain, moveValueSupplier, rotateValueSupplier, isFinished, false);
65 | }
66 |
67 | /**
68 | * Constructs a new {@link DriveArcade} command that moves the given
69 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
70 | * for linear and rotational movements.
71 | *
72 | * @param drivetrain the tank drivetrain this command operates on
73 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
74 | * Positive values go forwards
75 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
76 | * Positive values go clockwise
77 | * @param squareInputs whether to square the speed suppliers' values
78 | */
79 | public DriveArcade(TankDrivetrain drivetrain, Supplier moveValueSupplier,
80 | Supplier rotateValueSupplier, boolean squareInputs) {
81 | this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false, squareInputs);
82 | }
83 |
84 | /**
85 | * Constructs a new {@link DriveArcade} command that moves the given
86 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
87 | * for linear and rotational movements. Does not square the inputs.
88 | *
89 | * @param drivetrain the tank drivetrain this command operates on
90 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
91 | * Positive values go forwards
92 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
93 | * Positive values go clockwise
94 | */
95 | public DriveArcade(TankDrivetrain drivetrain, Supplier moveValueSupplier,
96 | Supplier rotateValueSupplier) {
97 | this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false, false);
98 | }
99 |
100 | /**
101 | * Constructs a new {@link DriveArcade} command that moves the given
102 | * {@link TankDrivetrain} according to speed values for linear and rotational movements.
103 | *
104 | * @param drivetrain the tank drivetrain this command operates on
105 | * @param moveValue the linear speed (-1 to 1). Positive values go forwards
106 | * @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
107 | * @param isFinished when to finish the command
108 | * @param squareInputs whether to square the speed values
109 | */
110 | public DriveArcade(TankDrivetrain drivetrain, double moveValue,
111 | double rotateValue, Supplier isFinished, boolean squareInputs) {
112 | this(drivetrain, () -> moveValue, () -> rotateValue, isFinished, squareInputs);
113 | }
114 |
115 | /**
116 | * Constructs a new {@link DriveArcade} command that moves the given
117 | * {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
118 | *
119 | * @param drivetrain the tank drivetrain this command operates on
120 | * @param moveValue the linear speed (-1 to 1). Positive values go forwards
121 | * @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
122 | * @param isFinished when to finish the command
123 | */
124 | public DriveArcade(TankDrivetrain drivetrain, double moveValue,
125 | double rotateValue, Supplier isFinished) {
126 | this(drivetrain, moveValue, rotateValue, isFinished, false);
127 | }
128 |
129 | /**
130 | * Constructs a new {@link DriveArcade} command that moves the given
131 | * {@link TankDrivetrain} according to speed values for linear and rotational movements.
132 | *
133 | * @param drivetrain the tank drivetrain this command operates on
134 | * @param moveValue the linear speed (-1 to 1). Positive values go forwards
135 | * @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
136 | * @param squareInputs whether to square the speed values
137 | */
138 | public DriveArcade(TankDrivetrain drivetrain, double moveValue,
139 | double rotateValue, boolean squareInputs) {
140 | this(drivetrain, moveValue, rotateValue, () -> false, squareInputs);
141 | }
142 |
143 | /**
144 | * Constructs a new {@link DriveArcade} command that moves the given
145 | * {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
146 | *
147 | * @param drivetrain the tank drivetrain this command operates on
148 | * @param moveValue the linear speed (-1 to 1). Positive values go forwards
149 | * @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
150 | */
151 | public DriveArcade(TankDrivetrain drivetrain, double moveValue,
152 | double rotateValue) {
153 | this(drivetrain, moveValue, rotateValue, () -> false, false);
154 | }
155 |
156 | @Override
157 | public void execute() {
158 | tankDrivetrain.arcadeDrive(moveValueSupplier.get(), rotateValueSupplier.get(), squareInputs);
159 | }
160 |
161 | @Override
162 | public boolean isFinished() {
163 | return isFinished.get();
164 | }
165 |
166 | @Override
167 | public void end(boolean interrupted) {
168 | tankDrivetrain.stop();
169 | }
170 | }
171 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveArcadeWithPID.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import com.spikes2212.control.FeedForwardController;
5 | import com.spikes2212.control.FeedForwardSettings;
6 | import com.spikes2212.control.PIDSettings;
7 | import edu.wpi.first.math.controller.PIDController;
8 | import edu.wpi.first.wpilibj.Timer;
9 | import edu.wpi.first.wpilibj2.command.Command;
10 |
11 | import java.util.function.Supplier;
12 |
13 | /**
14 | * A command that moves a {@link TankDrivetrain} with a set speed forward and with a PID loop to a certain angle.
15 | *
16 | * @author Yuval Levy
17 | * @see TankDrivetrain
18 | */
19 | public class DriveArcadeWithPID extends Command {
20 |
21 | /**
22 | * The drivetrain this command operates on.
23 | */
24 | protected final TankDrivetrain drivetrain;
25 |
26 | /**
27 | * The PID settings for the turning PID loop.
28 | */
29 | protected final PIDSettings pidSettings;
30 |
31 | /**
32 | * The PID controller for the turning PID loop.
33 | */
34 | protected final PIDController pidController;
35 |
36 | /**
37 | * The feed forward settings for the turning FeedForwards loop.
38 | */
39 | protected final FeedForwardSettings feedForwardSettings;
40 |
41 | /**
42 | * The feed forward controller for the turning FeedForwards loop.
43 | */
44 | protected final FeedForwardController feedForwardController;
45 |
46 | /**
47 | * The angle of the drivetrain.
48 | */
49 | protected final Supplier source;
50 |
51 | /**
52 | * The angle the drivetrain should reach.
53 | */
54 | protected final Supplier setpoint;
55 |
56 | /**
57 | * The acceleration the drivetrain should be at.
58 | */
59 | protected final Supplier acceleration;
60 |
61 | /**
62 | * The speed at which to move the drivetrain forward.
63 | */
64 | protected final Supplier moveValue;
65 |
66 | /**
67 | * The last time the drivetrain's angle wasn't within the target range.
68 | */
69 | private double lastTimeNotOnTarget;
70 |
71 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, Supplier setpoint,
72 | Supplier acceleration, Supplier moveValue, PIDSettings pidSettings,
73 | FeedForwardSettings feedForwardSettings) {
74 | addRequirements(drivetrain);
75 | this.drivetrain = drivetrain;
76 | this.setpoint = setpoint;
77 | this.acceleration = acceleration;
78 | this.pidSettings = pidSettings;
79 | this.feedForwardSettings = feedForwardSettings;
80 | this.source = source;
81 | this.moveValue = moveValue;
82 | this.pidController = new PIDController(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
83 | this.pidController.setSetpoint(setpoint.get());
84 | this.feedForwardController = new FeedForwardController(feedForwardSettings.getkS(), feedForwardSettings.getkV(),
85 | feedForwardSettings.getkA(), feedForwardSettings.getkG(), feedForwardSettings.getControlMode());
86 | }
87 |
88 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, double setpoint,
89 | Supplier acceleration, double moveValue, PIDSettings pidSettings,
90 | FeedForwardSettings feedForwardSettings) {
91 | this(drivetrain, source, () -> setpoint, acceleration, () -> moveValue, pidSettings, feedForwardSettings);
92 | }
93 |
94 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, Supplier setpoint,
95 | Supplier moveValue, PIDSettings pidSettings,
96 | FeedForwardSettings feedForwardSettings) {
97 | this(drivetrain, source, setpoint, () -> 0.0, moveValue, pidSettings, feedForwardSettings);
98 | }
99 |
100 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, double setpoint,
101 | double moveValue, PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
102 | this(drivetrain, source, () -> setpoint, () -> 0.0, () -> moveValue, pidSettings, feedForwardSettings);
103 | }
104 |
105 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, Supplier setpoint,
106 | Supplier moveValue, PIDSettings pidSettings) {
107 | this(drivetrain, source, setpoint, () -> 0.0, moveValue, pidSettings, FeedForwardSettings.EMPTY_FF_SETTINGS);
108 | }
109 |
110 | public DriveArcadeWithPID(TankDrivetrain drivetrain, Supplier source, double setpoint,
111 | double moveValue, PIDSettings pidSettings) {
112 | this(drivetrain, source, () -> setpoint, () -> moveValue, pidSettings);
113 | }
114 |
115 | @Override
116 | public void execute() {
117 | pidController.setTolerance(pidSettings.getTolerance());
118 | pidController.setPID(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
119 | pidController.setIZone(pidSettings.getIZone());
120 |
121 | feedForwardController.setGains(feedForwardSettings);
122 |
123 | drivetrain.arcadeDrive(moveValue.get(), pidController.calculate(source.get(), setpoint.get()) +
124 | feedForwardController.calculate(source.get(), setpoint.get(), acceleration.get()));
125 | }
126 |
127 | @Override
128 | public boolean isFinished() {
129 | if (!pidController.atSetpoint()) {
130 | lastTimeNotOnTarget = Timer.getFPGATimestamp();
131 | }
132 |
133 | return Timer.getFPGATimestamp() - lastTimeNotOnTarget >= pidSettings.getWaitTime();
134 | }
135 |
136 | @Override
137 | public void end(boolean interrupted) {
138 | drivetrain.stop();
139 | }
140 | }
141 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveArcadeWithVoltages.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * A command that moves a {@link TankDrivetrain} using linear and rotational voltages.
10 | *
11 | * @author Yorai Coval
12 | * @see TankDrivetrain
13 | */
14 |
15 | public class DriveArcadeWithVoltages extends Command {
16 |
17 | protected final TankDrivetrain tankDrivetrain;
18 | protected final Supplier moveValueSupplier;
19 | protected final Supplier rotateValueSupplier;
20 | protected final Supplier isFinished;
21 |
22 | /**
23 | * Constructs a new {@link DriveArcadeWithVoltages} command that moves the given
24 | * {@link TankDrivetrain} according to voltage values from Double {@link Supplier}s
25 | * for linear and rotational movements.
26 | *
27 | * @param drivetrain the tank drivetrain this command operates on
28 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear voltage (-12 to 12).
29 | * Positive values go forwards
30 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational voltage (-12 to 12).
31 | * Positive values go clockwise
32 | * @param isFinished when to finish the command
33 | */
34 | public DriveArcadeWithVoltages(TankDrivetrain drivetrain, Supplier moveValueSupplier,
35 | Supplier rotateValueSupplier, Supplier isFinished) {
36 | addRequirements(drivetrain);
37 | this.tankDrivetrain = drivetrain;
38 | this.moveValueSupplier = moveValueSupplier;
39 | this.rotateValueSupplier = rotateValueSupplier;
40 | this.isFinished = isFinished;
41 | }
42 |
43 | /**
44 | * Constructs a new {@link DriveArcadeWithVoltages} command that moves the given
45 | * {@link TankDrivetrain} according to voltage values from Double {@link Supplier}s
46 | * for linear and rotational movements.
47 | *
48 | * @param drivetrain the tank drivetrain this command operates on
49 | * @param moveValueSupplier the Double {@link Supplier} supplying the linear voltage (-12 to 12).
50 | * Positive values go forwards
51 | * @param rotateValueSupplier the Double {@link Supplier} supplying the rotational voltage (-12 to 12).
52 | * Positive values go clockwise
53 | */
54 | public DriveArcadeWithVoltages(TankDrivetrain drivetrain, Supplier moveValueSupplier,
55 | Supplier rotateValueSupplier) {
56 | this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false);
57 | }
58 |
59 | /**
60 | * Constructs a new {@link DriveArcadeWithVoltages} command that moves the given
61 | * {@link TankDrivetrain} according to voltage values for linear and rotational movements.
62 | *
63 | * @param drivetrain the tank drivetrain this command operates on
64 | * @param moveValue the linear voltage (-12 to 12). Positive values go forwards
65 | * @param rotateValue the rotational voltage (-12 to 12). Positive values go clockwise
66 | * @param isFinished when to finish the command
67 | */
68 | public DriveArcadeWithVoltages(TankDrivetrain drivetrain, double moveValue, double rotateValue,
69 | Supplier isFinished) {
70 | this(drivetrain, () -> moveValue, () -> rotateValue, isFinished);
71 | }
72 |
73 | /**
74 | * Constructs a new {@link DriveArcadeWithVoltages} command that moves the given
75 | * {@link TankDrivetrain} according to voltage values for linear and rotational movements.
76 | *
77 | * @param drivetrain the tank drivetrain this command operates on
78 | * @param moveValue the linear voltage (-12 to 12). Positive values go forwards
79 | * @param rotateValue the rotational voltage (-12 to 12). Positive values go clockwise
80 | */
81 | public DriveArcadeWithVoltages(TankDrivetrain drivetrain, double moveValue, double rotateValue) {
82 | this(drivetrain, () -> moveValue, () -> rotateValue, () -> false);
83 | }
84 |
85 | @Override
86 | public void execute() {
87 | tankDrivetrain.arcadeDriveVoltages(moveValueSupplier.get(), rotateValueSupplier.get());
88 | }
89 |
90 | @Override
91 | public boolean isFinished() {
92 | return isFinished.get();
93 | }
94 |
95 | @Override
96 | public void end(boolean interrupted) {
97 | tankDrivetrain.stop();
98 | }
99 | }
100 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveCurvature.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * A command that moves a {@link TankDrivetrain} while controlling the curvature of its path,
10 | * using the curvature drive method written by WPILib.
11 | *
12 | * @author Simon Kharmatsky
13 | * @see TankDrivetrain
14 | */
15 | public class DriveCurvature extends Command {
16 |
17 | protected final TankDrivetrain drivetrain;
18 | protected final Supplier speed;
19 | protected final Supplier rotation;
20 |
21 | public DriveCurvature(TankDrivetrain drivetrain, Supplier speed, Supplier rotation) {
22 | this.drivetrain = drivetrain;
23 | this.speed = speed;
24 | this.rotation = rotation;
25 | }
26 |
27 | public DriveCurvature(TankDrivetrain drivetrain, double speed, double rotation) {
28 | this(drivetrain, () -> speed, () -> rotation);
29 | }
30 |
31 | @Override
32 | public void execute() {
33 | drivetrain.curvatureDrive(speed.get(), rotation.get());
34 | }
35 |
36 | @Override
37 | public void end(boolean interrupted) {
38 | drivetrain.stop();
39 | }
40 | }
41 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveTank.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * A command that moves a {@link TankDrivetrain} using speeds supplied to the left and the right sides independently.
10 | *
11 | * @author Yuval Levy
12 | * @see TankDrivetrain
13 | */
14 | public class DriveTank extends Command {
15 |
16 | protected final TankDrivetrain tankDrivetrain;
17 | protected final Supplier leftSpeedSupplier;
18 | protected final Supplier rightSpeedSupplier;
19 | protected final Supplier isFinished;
20 | protected final boolean squareInputs;
21 |
22 | /**
23 | * This constructs a new {@link DriveTank} command that moves the given
24 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s for left and right sides.
25 | * Positive values move the drivetrain forward.
26 | *
27 | * @param drivetrain the tank drivetrain this command operates on
28 | * @param leftSpeedSupplier the Double {@link Supplier} supplying the left side's speed (-1 to 1).
29 | * Positive values go forward
30 | * @param rightSpeedSupplier the Double {@link Supplier} supplying the right side's speed (-1 to 1).
31 | * Positive values go forward
32 | * @param isFinished when to finish the command
33 | * @param squareInputs whether to square the speed suppliers' values
34 | */
35 | public DriveTank(TankDrivetrain drivetrain, Supplier leftSpeedSupplier,
36 | Supplier rightSpeedSupplier, Supplier isFinished, boolean squareInputs) {
37 | addRequirements(drivetrain);
38 | this.tankDrivetrain = drivetrain;
39 | this.leftSpeedSupplier = leftSpeedSupplier;
40 | this.rightSpeedSupplier = rightSpeedSupplier;
41 | this.isFinished = isFinished;
42 | this.squareInputs = squareInputs;
43 | }
44 |
45 | /**
46 | * This constructs a new {@link DriveTank} command that moves the given
47 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s for the left and right sides.
48 | * Positive values move the drivetrain forward. Does not square the inputs.
49 | *
50 | * @param drivetrain the tank drivetrain this command operates on
51 | * @param leftSpeedSupplier the Double {@link Supplier} supplying the left side's speed (-1 to 1).
52 | * Positive values go forward
53 | * @param rightSpeedSupplier the Double {@link Supplier} supplying the right side's speed (-1 to 1).
54 | * Positive values go forward
55 | * @param isFinished when to finish the command
56 | */
57 | public DriveTank(TankDrivetrain drivetrain, Supplier leftSpeedSupplier,
58 | Supplier rightSpeedSupplier, Supplier isFinished) {
59 | this(drivetrain, leftSpeedSupplier, rightSpeedSupplier, isFinished, false);
60 | }
61 |
62 | /**
63 | * This constructs a new {@link DriveTank} command that moves the given
64 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s for the left and right sides.
65 | * Positive values move the drivetrain forward.
66 | *
67 | * @param drivetrain the tank drivetrain this command operates on
68 | * @param leftSpeedSupplier the Double {@link Supplier} supplying the left side's speed (-1 to 1).
69 | * Positive values go forward
70 | * @param rightSpeedSupplier the Double {@link Supplier} supplying the right side's speed (-1 to 1).
71 | * Positive values go forward
72 | * @param squareInputs whether to square the speed suppliers' values
73 | */
74 | public DriveTank(TankDrivetrain drivetrain, Supplier leftSpeedSupplier,
75 | Supplier rightSpeedSupplier, boolean squareInputs) {
76 | this(drivetrain, leftSpeedSupplier, rightSpeedSupplier, () -> false, squareInputs);
77 | }
78 |
79 | /**
80 | * This constructs a new {@link DriveTank} command that moves the given
81 | * {@link TankDrivetrain} according to speed values from Double {@link Supplier}s for the left and right sides.
82 | * Positive values move the drivetrain forward. Does not square the inputs.
83 | *
84 | * @param drivetrain the tank drivetrain this command operates on
85 | * @param leftSpeedSupplier the Double {@link Supplier} supplying the left side's speed (-1 to 1).
86 | * Positive values go forward
87 | * @param rightSpeedSupplier the Double {@link Supplier} supplying the right side's speed (-1 to 1).
88 | * Positive values go forward
89 | */
90 | public DriveTank(TankDrivetrain drivetrain, Supplier leftSpeedSupplier,
91 | Supplier rightSpeedSupplier) {
92 | this(drivetrain, leftSpeedSupplier, rightSpeedSupplier, () -> false, false);
93 | }
94 |
95 | /**
96 | * This constructs a new {@link DriveTank} command that moves the given
97 | * {@link TankDrivetrain} according to speed values for the left and right sides.
98 | * Positive values move the drivetrain forward.
99 | *
100 | * @param drivetrain the tank drivetrain this command operates on
101 | * @param leftSpeed the left side's speed (-1 to 1). Positive values go forward
102 | * @param rightSpeed the right side's speed (-1 to 1). Positive values go forward
103 | * @param isFinished when to finish the command
104 | * @param squareInputs whether to square the speed values
105 | */
106 | public DriveTank(TankDrivetrain drivetrain, double leftSpeed,
107 | double rightSpeed, Supplier isFinished, boolean squareInputs) {
108 | this(drivetrain, () -> leftSpeed, () -> rightSpeed, isFinished, squareInputs);
109 | }
110 |
111 | /**
112 | * This constructs a new {@link DriveTank} command that moves the given
113 | * {@link TankDrivetrain} according to speed values for the left and right sides.
114 | * Positive values move the drivetrain forward. Does not square the inputs.
115 | *
116 | * @param drivetrain the tank drivetrain this command operates on
117 | * @param leftSpeed the left side's speed (-1 to 1). Positive values go forward
118 | * @param rightSpeed the right side's speed (-1 to 1). Positive values go forward
119 | * @param isFinished when to finish the command
120 | */
121 | public DriveTank(TankDrivetrain drivetrain, double leftSpeed, double rightSpeed, Supplier isFinished) {
122 | this(drivetrain, leftSpeed, rightSpeed, isFinished, false);
123 | }
124 |
125 | /**
126 | * This constructs a new {@link DriveTank} command that moves the given
127 | * {@link TankDrivetrain} according to speed values for the left and right sides.
128 | * Positive values move the drivetrain forward.
129 | *
130 | * @param drivetrain the tank drivetrain this command operates on
131 | * @param leftSpeed the left side's speed (-1 to 1). Positive values go forward
132 | * @param rightSpeed the right side's speed (-1 to 1). Positive values go forward
133 | * @param squareInputs whether to square the speed values
134 | */
135 | public DriveTank(TankDrivetrain drivetrain, double leftSpeed, double rightSpeed, boolean squareInputs) {
136 | this(drivetrain, leftSpeed, rightSpeed, () -> false, squareInputs);
137 | }
138 |
139 | /**
140 | * This constructs a new {@link DriveTank} command that moves the given
141 | * {@link TankDrivetrain} according to speed values for the left and right sides.
142 | * Positive values move the drivetrain forward. Does not square the inputs.
143 | *
144 | * @param drivetrain the tank drivetrain this command operates on
145 | * @param leftSpeed the left side's speed (-1 to 1). Positive values go forward
146 | * @param rightSpeed the right side's speed (-1 to 1). Positive values go forward
147 | */
148 | public DriveTank(TankDrivetrain drivetrain, double leftSpeed, double rightSpeed) {
149 | this(drivetrain, leftSpeed, rightSpeed, () -> false, false);
150 | }
151 |
152 | @Override
153 | public void execute() {
154 | tankDrivetrain.tankDrive(leftSpeedSupplier.get(), rightSpeedSupplier.get(), squareInputs);
155 | }
156 |
157 | @Override
158 | public boolean isFinished() {
159 | return isFinished.get();
160 | }
161 |
162 | @Override
163 | public void end(boolean interrupted) {
164 | tankDrivetrain.stop();
165 | }
166 | }
167 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/DriveTankWithVoltages.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * A command that moves a {@link TankDrivetrain} using voltage supplied to the left and the right sides independently.
10 | *
11 | * @author Yorai Coval
12 | * @see TankDrivetrain
13 | */
14 | public class DriveTankWithVoltages extends Command {
15 |
16 | protected final Supplier leftVoltageSupplier;
17 | protected final Supplier rightVoltageSupplier;
18 | protected final TankDrivetrain drivetrain;
19 | protected final Supplier isFinished;
20 |
21 | /**
22 | * This constructs a new {@link DriveTankWithVoltages} command that moves the given {@link TankDrivetrain} according to voltage
23 | * values from Double {@link Supplier}s for the left and right sides.
24 | * Positive values move the drivetrain forward.
25 | *
26 | * @param drivetrain the drivetrain this command requires and moves
27 | * @param leftVoltageSupplier the Double {@link Supplier} supplying the voltage for the left side (-12 to 12)
28 | * @param rightVoltageSupplier the Double {@link Supplier} supplying the voltage for the right side (-12 to 12)
29 | * @param isFinished when to finish the command
30 | */
31 | public DriveTankWithVoltages(TankDrivetrain drivetrain, Supplier leftVoltageSupplier,
32 | Supplier rightVoltageSupplier, Supplier isFinished) {
33 | this.drivetrain = drivetrain;
34 | this.leftVoltageSupplier = leftVoltageSupplier;
35 | this.rightVoltageSupplier = rightVoltageSupplier;
36 | this.isFinished = isFinished;
37 | }
38 |
39 | /**
40 | * This constructs a new {@link DriveTankWithVoltages} command that moves the given {@link TankDrivetrain} according to voltage
41 | * values from Double {@link Supplier}s for the left and right sides.
42 | * Positive values move the drivetrain forward.
43 | *
44 | * @param drivetrain the drivetrain this command requires and moves
45 | * @param leftVoltageSupplier the Double {@link Supplier} supplying the voltage for the left side (-12 to 12)
46 | * @param rightVoltageSupplier the Double {@link Supplier} supplying the voltage for the right side (-12 to 12)
47 | */
48 | public DriveTankWithVoltages(TankDrivetrain drivetrain, Supplier leftVoltageSupplier,
49 | Supplier rightVoltageSupplier) {
50 | this(drivetrain, leftVoltageSupplier, rightVoltageSupplier, () -> false);
51 | }
52 |
53 | /**
54 | * This constructs a new {@link DriveTankWithVoltages} command that moves the given {@link TankDrivetrain} according to voltage
55 | * values for the left and right sides.
56 | * Positive values move the drivetrain forward.
57 | *
58 | * @param drivetrain the drivetrain this command requires and moves
59 | * @param leftVoltage the voltage for the left side (-12 to 12)
60 | * @param rightVoltage the voltage for the right side (-12 to 12)
61 | * @param isFinished when to finish the command
62 | */
63 | public DriveTankWithVoltages(TankDrivetrain drivetrain, double leftVoltage, double rightVoltage,
64 | Supplier isFinished) {
65 | this(drivetrain, () -> leftVoltage, () -> rightVoltage, isFinished);
66 | }
67 |
68 | /**
69 | * This constructs a new {@link DriveTankWithVoltages} command that moves the given {@link TankDrivetrain} according to voltage
70 | * values for the left and right sides.
71 | * Positive values move the drivetrain forward.
72 | *
73 | * @param drivetrain the drivetrain this command requires and moves
74 | * @param leftVoltage the voltage for the left side (-12 to 12)
75 | * @param rightVoltage the voltage for the right side (-12 to 12)
76 | */
77 | public DriveTankWithVoltages(TankDrivetrain drivetrain, double leftVoltage, double rightVoltage) {
78 | this(drivetrain, () -> leftVoltage, () -> rightVoltage, () -> false);
79 | }
80 |
81 | @Override
82 | public void execute() {
83 | drivetrain.tankDriveVoltages(leftVoltageSupplier.get(), rightVoltageSupplier.get());
84 | }
85 |
86 | @Override
87 | public boolean isFinished() {
88 | return isFinished.get();
89 | }
90 |
91 | @Override
92 | public void end(boolean interrupted) {
93 | drivetrain.stop();
94 | }
95 | }
96 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/FollowPath.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.OdometryDrivetrain;
4 | import com.spikes2212.control.FeedForwardController;
5 | import com.spikes2212.control.FeedForwardSettings;
6 | import com.spikes2212.control.PIDSettings;
7 | import com.spikes2212.path.PurePursuitController;
8 | import com.spikes2212.path.Waypoint;
9 | import edu.wpi.first.math.controller.PIDController;
10 | import edu.wpi.first.wpilibj2.command.Command;
11 |
12 | import java.util.List;
13 |
14 | @Deprecated(forRemoval = true, since = "2025")
15 | public class FollowPath extends Command {
16 |
17 | private OdometryDrivetrain drivetrain;
18 | private List path;
19 | private double lookaheadDistance;
20 | private double maxAcceleration;
21 | private PurePursuitController purePursuitController;
22 | private FeedForwardController rightFeedForwardController;
23 | private FeedForwardController leftFeedForwardController;
24 | private PIDSettings pidSettings;
25 | private FeedForwardSettings FeedForwardSettings;
26 | private PIDController leftController;
27 | private PIDController rightController;
28 |
29 | public FollowPath(OdometryDrivetrain drivetrain, List path, double lookaheadDistance,
30 | PIDSettings pidSettings, FeedForwardSettings feedForwardSettings, double maxAcceleration,
31 | boolean inverted) {
32 | addRequirements(drivetrain);
33 | this.drivetrain = drivetrain;
34 | this.path = path;
35 | this.lookaheadDistance = lookaheadDistance;
36 | this.pidSettings = pidSettings;
37 | this.FeedForwardSettings = feedForwardSettings;
38 | this.maxAcceleration = maxAcceleration;
39 | drivetrain.setInverted(inverted);
40 | }
41 |
42 | @Override
43 | public void initialize() {
44 | drivetrain.zeroSensors();
45 | purePursuitController = new PurePursuitController(drivetrain.getHandler(), path,
46 | lookaheadDistance, maxAcceleration, drivetrain.getWidth());
47 | purePursuitController.getOdometryHandler().set(0, 0);
48 | purePursuitController.reset();
49 | leftFeedForwardController = new FeedForwardController(FeedForwardSettings.getkV(), FeedForwardSettings.getkA(),
50 | FeedForwardSettings.getControlMode());
51 | rightFeedForwardController = new FeedForwardController(FeedForwardSettings.getkV(), FeedForwardSettings.getkA(),
52 | FeedForwardSettings.getControlMode());
53 | leftController = new PIDController(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
54 | rightController = new PIDController(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
55 | }
56 |
57 | @Override
58 | public void execute() {
59 | double[] speeds = purePursuitController.getTargetSpeeds();
60 | double leftSpeed = leftFeedForwardController.calculate(drivetrain.getLeftRate(), speeds[0]) +
61 | leftController.calculate(drivetrain.getLeftRate(), speeds[0]
62 | );
63 | double rightSpeed = rightFeedForwardController.calculate(drivetrain.getRightRate(), speeds[1]) +
64 | rightController.calculate(drivetrain.getRightRate(), speeds[1]
65 | );
66 | drivetrain.tankDrive(leftSpeed, rightSpeed, false);
67 | }
68 |
69 | @Override
70 | public void end(boolean interrupted) {
71 | drivetrain.stop();
72 | }
73 |
74 | @Override
75 | public boolean isFinished() {
76 | return purePursuitController.done();
77 | }
78 | }
79 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/OrientWithPID.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 |
7 | import java.util.function.Supplier;
8 |
9 | @Deprecated(forRemoval = true, since = "2025")
10 | public class OrientWithPID extends DriveArcadeWithPID {
11 |
12 | public OrientWithPID(TankDrivetrain drivetrain, Supplier source, Supplier setpoint,
13 | PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
14 | super(drivetrain, source, setpoint, () -> 0.0, pidSettings, feedForwardSettings);
15 | }
16 |
17 | public OrientWithPID(TankDrivetrain drivetrain, Supplier source, double setpoint, PIDSettings pidSettings,
18 | FeedForwardSettings feedForwardSettings) {
19 | this(drivetrain, source, () -> setpoint, pidSettings, feedForwardSettings);
20 | }
21 |
22 | public OrientWithPID(TankDrivetrain drivetrain, Supplier source, Supplier setpoint,
23 | PIDSettings pidSettings) {
24 | this(drivetrain, source, setpoint, pidSettings, FeedForwardSettings.EMPTY_FF_SETTINGS);
25 | }
26 |
27 | public OrientWithPID(TankDrivetrain drivetrain, Supplier source, double setpoint, PIDSettings pidSettings) {
28 | this(drivetrain, source, setpoint, pidSettings, FeedForwardSettings.EMPTY_FF_SETTINGS);
29 | }
30 | }
31 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/smartmotorcontrollerdrivetrain/MoveSmartMotorControllerTankDrivetrain.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands.smartmotorcontrollerdrivetrain;
2 |
3 | import com.spikes2212.command.drivetrains.smartmotorcontrollerdrivetrain.SmartMotorControllerTankDrivetrain;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.util.UnifiedControlMode;
7 | import edu.wpi.first.wpilibj.Timer;
8 | import edu.wpi.first.wpilibj2.command.Command;
9 |
10 | import java.util.function.Supplier;
11 |
12 | /**
13 | * A command that moves a {@link SmartMotorControllerTankDrivetrain} using its master motor controllers' control loops.
14 | *
15 | * @author Yoel Perman Brilliant
16 | * @see SmartMotorControllerTankDrivetrain
17 | */
18 | public class MoveSmartMotorControllerTankDrivetrain extends Command {
19 |
20 | /**
21 | * The {@link SmartMotorControllerTankDrivetrain} this command will run on.
22 | */
23 | protected final SmartMotorControllerTankDrivetrain drivetrain;
24 |
25 | /**
26 | * The left side loop's PID constants.
27 | */
28 | protected final PIDSettings leftPIDSettings;
29 |
30 | /**
31 | * The right side loop's PID constants.
32 | */
33 | protected final PIDSettings rightPIDSettings;
34 |
35 | /**
36 | * The loop's feed forward gains.
37 | */
38 | protected final FeedForwardSettings feedForwardSettings;
39 |
40 | /**
41 | * The loop's control mode (e.g. voltage, velocity, position...).
42 | */
43 | protected final UnifiedControlMode controlMode;
44 |
45 | /**
46 | * The setpoint this command should bring the left side of the {@link SmartMotorControllerTankDrivetrain} to.
47 | */
48 | protected final Supplier leftSetpoint;
49 |
50 | /**
51 | * The setpoint this command should bring the right side of the {@link SmartMotorControllerTankDrivetrain} to.
52 | */
53 | protected final Supplier rightSetpoint;
54 |
55 | /**
56 | * The most recent timestamp on which the left side's loop has not reached its target setpoint.
57 | */
58 | private double lastTimeLeftNotOnTarget;
59 |
60 | /**
61 | * The most recent timestamp on which the right side's loop has not reached its target setpoint.
62 | */
63 | private double lastTimeRightNotOnTarget;
64 |
65 | /**
66 | * Constructs a new instance of {@link MoveSmartMotorControllerTankDrivetrain}.
67 | *
68 | * @param drivetrain the {@link SmartMotorControllerTankDrivetrain} this command will run on
69 | * @param leftPIDSettings the left side's loop's PID constants
70 | * @param rightPIDSettings the right side's loop's PID constants
71 | * @param feedForwardSettings the loops' feed forward gains
72 | * @param controlMode the loops' control mode (e.g. voltage, velocity, position...)
73 | * @param leftSetpoint the setpoint this command should bring the
74 | * {@link SmartMotorControllerTankDrivetrain}'s left side to
75 | * @param rightSetpoint the setpoint this command should bring the
76 | * {@link SmartMotorControllerTankDrivetrain}'s right side to
77 | */
78 | public MoveSmartMotorControllerTankDrivetrain(SmartMotorControllerTankDrivetrain drivetrain,
79 | PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
80 | FeedForwardSettings feedForwardSettings,
81 | UnifiedControlMode controlMode, Supplier leftSetpoint,
82 | Supplier rightSetpoint) {
83 | addRequirements(drivetrain);
84 | this.drivetrain = drivetrain;
85 | this.controlMode = controlMode;
86 | this.leftPIDSettings = leftPIDSettings;
87 | this.rightPIDSettings = rightPIDSettings;
88 | this.feedForwardSettings = feedForwardSettings;
89 | this.leftSetpoint = leftSetpoint;
90 | this.rightSetpoint = rightSetpoint;
91 | this.lastTimeLeftNotOnTarget = 0;
92 | this.lastTimeRightNotOnTarget = 0;
93 | }
94 |
95 | /**
96 | * Configures the drivetrain's control loops.
97 | */
98 | @Override
99 | public void initialize() {
100 | drivetrain.configureLoop(leftPIDSettings, rightPIDSettings, feedForwardSettings);
101 | }
102 |
103 | /**
104 | * Updates any control loops running on the drivetrain's motor controllers.
105 | */
106 | @Override
107 | public void execute() {
108 | drivetrain.pidSet(controlMode, leftSetpoint.get(), rightSetpoint.get(), leftPIDSettings,
109 | rightPIDSettings, feedForwardSettings);
110 | }
111 |
112 | @Override
113 | public void end(boolean interrupted) {
114 | drivetrain.finish();
115 | }
116 |
117 | /**
118 | * Checks if the drivetrain has been at its target setpoint for longer than its allowed wait time.
119 | *
120 | * @return {@code true} if the command should finish running, {@code false} otherwise
121 | */
122 | @Override
123 | public boolean isFinished() {
124 | double now = Timer.getFPGATimestamp();
125 | if (!drivetrain.leftOnTarget(controlMode, leftPIDSettings.getTolerance(), leftSetpoint.get())) {
126 | lastTimeLeftNotOnTarget = now;
127 | }
128 | if (!drivetrain.rightOnTarget(controlMode, rightPIDSettings.getTolerance(), rightSetpoint.get())) {
129 | lastTimeRightNotOnTarget = now;
130 | }
131 | return now - lastTimeLeftNotOnTarget >= leftPIDSettings.getWaitTime() &&
132 | now - lastTimeRightNotOnTarget >= rightPIDSettings.getWaitTime();
133 | }
134 | }
135 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/commands/smartmotorcontrollerdrivetrain/MoveSmartMotorControllerTankDrivetrainTrapezically.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.commands.smartmotorcontrollerdrivetrain;
2 |
3 | import com.spikes2212.command.drivetrains.smartmotorcontrollerdrivetrain.SmartMotorControllerTankDrivetrain;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.control.TrapezoidProfileSettings;
7 | import com.spikes2212.util.UnifiedControlMode;
8 |
9 | import java.util.function.Supplier;
10 |
11 | /**
12 | * A command that moves a {@link SmartMotorControllerTankDrivetrain} by running a trapezoid profile control loop on its
13 | * master motor controllers.
14 | *
15 | * @author Yoel Perman Brilliant
16 | * @see SmartMotorControllerTankDrivetrain
17 | * @see MoveSmartMotorControllerTankDrivetrain
18 | */
19 | public class MoveSmartMotorControllerTankDrivetrainTrapezically extends MoveSmartMotorControllerTankDrivetrain {
20 |
21 | /**
22 | * The loops' trapezoid profile configurations.
23 | */
24 | protected final TrapezoidProfileSettings trapezoidProfileSettings;
25 |
26 | /**
27 | * Constructs a new instance of {@link MoveSmartMotorControllerTankDrivetrainTrapezically}.
28 | *
29 | * @param drivetrain the {@link SmartMotorControllerTankDrivetrain} this command will run on
30 | * @param leftPIDSettings the left side's loop's PID constants
31 | * @param rightPIDSettings the right side's loop's PID constants
32 | * @param feedForwardSettings the loop's feed forward gains
33 | * @param leftSetpoint the setpoint this command should bring the
34 | * {@link SmartMotorControllerTankDrivetrain}'s left side to
35 | * @param rightSetpoint the setpoint this command should bring the
36 | * {@link SmartMotorControllerTankDrivetrain}'s right side to
37 | * @param trapezoidProfileSettings the trapezoid profile settings
38 | */
39 | public MoveSmartMotorControllerTankDrivetrainTrapezically(SmartMotorControllerTankDrivetrain drivetrain,
40 | PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
41 | FeedForwardSettings feedForwardSettings,
42 | Supplier leftSetpoint,
43 | Supplier rightSetpoint,
44 | TrapezoidProfileSettings trapezoidProfileSettings) {
45 | super(drivetrain, leftPIDSettings, rightPIDSettings, feedForwardSettings, UnifiedControlMode.TRAPEZOID_PROFILE,
46 | leftSetpoint, rightSetpoint);
47 | this.trapezoidProfileSettings = trapezoidProfileSettings;
48 | }
49 |
50 | @Override
51 | public void initialize() {
52 | drivetrain.configureLoop(leftPIDSettings, rightPIDSettings, feedForwardSettings, trapezoidProfileSettings);
53 | }
54 |
55 | @Override
56 | public void execute() {
57 | drivetrain.pidSet(controlMode, leftSetpoint.get(), rightSetpoint.get(), leftPIDSettings, rightPIDSettings,
58 | feedForwardSettings, trapezoidProfileSettings);
59 | }
60 | }
61 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/drivetrains/smartmotorcontrollerdrivetrain/SmartMotorControllerTankDrivetrain.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.drivetrains.smartmotorcontrollerdrivetrain;
2 |
3 | import com.spikes2212.command.drivetrains.TankDrivetrain;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.control.TrapezoidProfileSettings;
7 | import com.spikes2212.util.UnifiedControlMode;
8 | import edu.wpi.first.wpilibj2.command.Subsystem;
9 |
10 | /**
11 | * A {@link TankDrivetrain} that runs control loops on an applicable motor controllers.
12 | *
13 | * @author Yoel Perman Brilliant
14 | */
15 | public interface SmartMotorControllerTankDrivetrain extends Subsystem {
16 |
17 | /**
18 | * Configures the loop's PID constants and feed forward gains.
19 | */
20 | default void configPIDF(PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
21 | FeedForwardSettings feedForwardSettings) {
22 | }
23 |
24 | /**
25 | * Configures the loop's trapezoid profile settings.
26 | */
27 | default void configureTrapezoid(TrapezoidProfileSettings settings) {
28 | }
29 |
30 | /**
31 | * Configures the loop's settings.
32 | */
33 | default void configureLoop(PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
34 | FeedForwardSettings feedForwardSettings,
35 | TrapezoidProfileSettings trapezoidProfileSettings) {
36 | configPIDF(leftPIDSettings, rightPIDSettings, feedForwardSettings);
37 | configureTrapezoid(trapezoidProfileSettings);
38 | }
39 |
40 | /**
41 | * Configures the loop's settings.
42 | */
43 | default void configureLoop(PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
44 | FeedForwardSettings feedForwardSettings) {
45 | configureLoop(leftPIDSettings, rightPIDSettings, feedForwardSettings,
46 | TrapezoidProfileSettings.EMPTY_TRAPEZOID_PROFILE_SETTINGS);
47 | }
48 |
49 | /**
50 | * Updates any control loops running on the drivetrain's motor controllers.
51 | *
52 | * @param controlMode the loops' control type (e.g. voltage, velocity, position...)
53 | * @param leftSetpoint the left side loop's target setpoint
54 | * @param rightSetpoint the right side loop's target setpoint
55 | * @param leftPIDSettings the left side's PID constants
56 | * @param rightPIDSettings the right side's PID constants
57 | * @param feedForwardSettings the feed forward gains
58 | * @param trapezoidProfileSettings the trapezoid profile settings
59 | */
60 | void pidSet(UnifiedControlMode controlMode, double leftSetpoint, double rightSetpoint, PIDSettings leftPIDSettings,
61 | PIDSettings rightPIDSettings, FeedForwardSettings feedForwardSettings,
62 | TrapezoidProfileSettings trapezoidProfileSettings);
63 |
64 | /**
65 | * Updates any control loops running on the drivetrain's motor controllers.
66 | *
67 | * @param controlMode the loops' control type (e.g. voltage, velocity, position...)
68 | * @param leftSetpoint the left side loop's target setpoint
69 | * @param rightSetpoint the right side loop's target setpoint
70 | * @param leftPIDSettings the left side's PID constants
71 | * @param rightPIDSettings the right side's PID constants
72 | * @param feedForwardSettings the feed forward gains
73 | */
74 | default void pidSet(UnifiedControlMode controlMode, double leftSetpoint, double rightSetpoint,
75 | PIDSettings leftPIDSettings, PIDSettings rightPIDSettings,
76 | FeedForwardSettings feedForwardSettings) {
77 | pidSet(controlMode, leftSetpoint, rightSetpoint, leftPIDSettings, rightPIDSettings, feedForwardSettings,
78 | TrapezoidProfileSettings.EMPTY_TRAPEZOID_PROFILE_SETTINGS);
79 | }
80 |
81 | /**
82 | * Stops any control loops running on the drivetrain's motor controllers.
83 | */
84 | default void finish() {
85 | }
86 |
87 | /**
88 | * Checks whether the loops are currently on the target setpoints.
89 | *
90 | * @param controlMode the loops' control type (e.g. voltage, velocity, position...)
91 | * @param leftTolerance the maximum difference from the left target to still consider the left loop to be on target
92 | * @param rightTolerance the maximum difference from the right target to still consider the right loop to be
93 | * on target
94 | * @param leftSetpoint the left side's wanted setpoint
95 | * @param rightSetpoint the right side's wanted setpoint
96 | * @return {@code true} when on target setpoint, {@code false} otherwise
97 | */
98 | default boolean onTarget(UnifiedControlMode controlMode, double leftTolerance, double rightTolerance,
99 | double leftSetpoint, double rightSetpoint) {
100 | return leftOnTarget(controlMode, leftTolerance, leftSetpoint) &&
101 | rightOnTarget(controlMode, rightTolerance, rightSetpoint);
102 | }
103 |
104 | /**
105 | * Checks whether the left side's loop is currently on the target setpoint.
106 | *
107 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
108 | * @param tolerance the maximum difference from the target to still consider the left loop to be on target
109 | * @param setpoint the wanted setpoint
110 | * @return {@code true} when on target setpoint, {@code false} otherwise
111 | */
112 | boolean leftOnTarget(UnifiedControlMode controlMode, double tolerance, double setpoint);
113 |
114 | /**
115 | * Checks whether the right side's loop is currently on the target setpoint.
116 | *
117 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
118 | * @param tolerance the maximum difference from the target to still consider the right loop to be on target
119 | * @param setpoint the wanted setpoint
120 | * @return {@code true} when on target setpoint, {@code false} otherwise
121 | */
122 | boolean rightOnTarget(UnifiedControlMode controlMode, double tolerance, double setpoint);
123 | }
124 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/GenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem;
2 |
3 |
4 | import com.spikes2212.command.DashboardedSubsystem;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * This class represents a generic subsystem that moves within a limitation, or without one.
10 | *
11 | * @author Yuval Levy
12 | * @see DashboardedSubsystem
13 | */
14 | public abstract class GenericSubsystem extends DashboardedSubsystem {
15 |
16 | private static final String DEFAULT_NAMESPACE_NAME = "generic subsystem";
17 |
18 | protected final Supplier maxSpeed;
19 | protected final Supplier minSpeed;
20 |
21 | private double currentSpeed = 0;
22 |
23 | /**
24 | * Constructs a new instance of {@link GenericSubsystem} with the given minimum speed supplier
25 | * and maximum speed supplier.
26 | *
27 | * @param minSpeed the minimum speed
28 | * @param maxSpeed the maximum speed
29 | */
30 | public GenericSubsystem(String namespaceName, Supplier minSpeed, Supplier maxSpeed) {
31 | super(namespaceName);
32 | this.maxSpeed = maxSpeed;
33 | this.minSpeed = minSpeed;
34 | }
35 |
36 | /**
37 | * Constructs a new instance of {@link GenericSubsystem}.
38 | *
39 | * @param namespaceName the name of the subsystem's namespace
40 | */
41 | public GenericSubsystem(String namespaceName) {
42 | this(namespaceName, -1, 1);
43 | }
44 |
45 | /**
46 | * Constructs a new instance of {@link GenericSubsystem} with the given minimum speed and maximum speed.
47 | *
48 | * @param namespaceName the name of the subsystem's namespace
49 | * @param minSpeed the minimum speed
50 | * @param maxSpeed the maximum speed
51 | */
52 | public GenericSubsystem(String namespaceName, double minSpeed, double maxSpeed) {
53 | this(namespaceName, () -> minSpeed, () -> maxSpeed);
54 | }
55 |
56 | /**
57 | * Moves this {@link GenericSubsystem} with the given speed, as long as it is
58 | * within the limits specified when this {@link GenericSubsystem} was constructed.
59 | *
60 | * @param speed the speed to move the subsystem with.
61 | */
62 | public final void move(double speed) {
63 | if (speed < minSpeed.get()) speed = minSpeed.get();
64 | if (speed > maxSpeed.get()) speed = maxSpeed.get();
65 | if (canMove(speed)) {
66 | apply(speed);
67 | currentSpeed = speed;
68 | }
69 | }
70 |
71 | /**
72 | * This method applies a given speed to the subsystem.
73 | *
74 | * @param speed the speed
75 | */
76 | protected abstract void apply(double speed);
77 |
78 | /**
79 | * This method returns whether the subsystem can move safely.
80 | *
81 | * @param speed the speed
82 | * @return whether the subsystem can move safely
83 | */
84 | public abstract boolean canMove(double speed);
85 |
86 | /**
87 | * Stops this subsystem's movement.
88 | */
89 | public abstract void stop();
90 |
91 | /**
92 | * Return the current speed of this {@link GenericSubsystem}.
93 | *
94 | * @return the current speed of this {@link GenericSubsystem}.
95 | */
96 | public double getSpeed() {
97 | return currentSpeed;
98 | }
99 | }
100 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/MotoredGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem;
2 |
3 | import com.spikes2212.dashboard.Namespace;
4 | import com.spikes2212.util.MotorControllerGroup;
5 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
6 |
7 | import java.util.function.Supplier;
8 |
9 | /**
10 | * A motor controlled generic subsystem.
11 | *
12 | * @author Ofri Rosenbaum
13 | * @see GenericSubsystem
14 | */
15 | public class MotoredGenericSubsystem extends GenericSubsystem {
16 |
17 | protected final MotorController motorController;
18 |
19 | /**
20 | * Constructs a new instance of {@link MotoredGenericSubsystem} with the given {@link Namespace}'s name, the given
21 | * minSpeed supplier, the given maxSpeed supplier and the given {@link MotorController}s.
22 | *
23 | * @param namespaceName the name of the subsystem's namespace
24 | * @param minSpeed the minimum speed
25 | * @param maxSpeed the maximum speed
26 | * @param motorControllers the motor controllers in the subsystem
27 | */
28 | public MotoredGenericSubsystem(String namespaceName, Supplier minSpeed, Supplier maxSpeed,
29 | MotorController... motorControllers) {
30 | super(namespaceName, minSpeed, maxSpeed);
31 | this.motorController = new MotorControllerGroup(motorControllers);
32 | }
33 |
34 | /**
35 | * Constructs a new instance of {@link MotoredGenericSubsystem} with the given {@link Namespace}'s name, the given
36 | * minSpeed, maxSpeed and the given {@link MotorController}s.
37 | *
38 | * @param namespaceName the name of the subsystem's namespace
39 | * @param minSpeed the minimum speed
40 | * @param maxSpeed the maximum speed
41 | * @param motorControllers the motor controllers in the subsystem
42 | */
43 | public MotoredGenericSubsystem(String namespaceName, double minSpeed, double maxSpeed,
44 | MotorController... motorControllers) {
45 | this(namespaceName, () -> minSpeed, () -> maxSpeed, motorControllers);
46 | }
47 |
48 | /**
49 | * Constructs a new instance of {@link MotoredGenericSubsystem} with the given {@link Namespace}'s name and
50 | * the given {@link MotorController}s.
51 | *
52 | * @param namespaceName the name of the subsystem's namespace
53 | * @param motorControllers the motor controllers in the subsystem
54 | */
55 | public MotoredGenericSubsystem(String namespaceName, MotorController... motorControllers) {
56 | this(namespaceName, () -> -1.0, () -> 1.0, motorControllers);
57 | }
58 |
59 | @Override
60 | protected void apply(double speed) {
61 | motorController.set(speed);
62 | }
63 |
64 | @Override
65 | public boolean canMove(double speed) {
66 | return true;
67 | }
68 |
69 | @Override
70 | public void stop() {
71 | motorController.stopMotor();
72 | }
73 |
74 | /**
75 | * Adds any commands or data from this subsystem to the dashboard.
76 | */
77 | @Override
78 | public void configureDashboard() {
79 | }
80 | }
81 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/AccelerateGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands;
2 |
3 | import com.spikes2212.command.genericsubsystem.GenericSubsystem;
4 | import edu.wpi.first.wpilibj.Timer;
5 |
6 | import java.util.function.Supplier;
7 |
8 | /**
9 | * This command accelerate the speed of a {@link GenericSubsystem} linearly,
10 | * so it will reach a wanted speed after a given time.
11 | *
12 | * @author Yuval Levy
13 | * @see MoveGenericSubsystem
14 | */
15 | @Deprecated(forRemoval = true, since = "2025")
16 | public class AccelerateGenericSubsystem extends MoveGenericSubsystem {
17 |
18 | protected final double time;
19 | private double acceleration;
20 | private double currentSpeed;
21 | private double startTime;
22 |
23 | /**
24 | * This constructs a new {@link AccelerateGenericSubsystem} command using the
25 | * {@link GenericSubsystem} this command operates on and a supplier supplying the
26 | * wanted speed the {@link GenericSubsystem} should move with after the given
27 | * time.
28 | *
29 | * @param subsystem the {@link GenericSubsystem} this command should move.
30 | * @param wantedSpeed the speed the subsystem should move after the time.
31 | * @param time the time it takes for the subsystem to get to the speed.
32 | */
33 | public AccelerateGenericSubsystem(GenericSubsystem subsystem, Supplier wantedSpeed, double time) {
34 | super(subsystem, wantedSpeed);
35 | if (time <= 1) {
36 | time = 1;
37 | }
38 | this.time = time;
39 | }
40 |
41 | /**
42 | * This constructs a new {@link AccelerateGenericSubsystem} command using the
43 | * {@link GenericSubsystem} this command operates on and a supplier supplying the
44 | * wanted speed the {@link GenericSubsystem} should move with after the given
45 | * time.
46 | *
47 | * @param subsystem the {@link GenericSubsystem} this command should move.
48 | * @param wantedSpeed the speed the subsystem should move after the time.
49 | * @param time the time it takes for the subsystem to get to the speed.
50 | */
51 | public AccelerateGenericSubsystem(GenericSubsystem subsystem, double wantedSpeed, double time) {
52 | this(subsystem, () -> wantedSpeed, time);
53 | }
54 |
55 | /**
56 | * Reset the timer.
57 | */
58 | @Override
59 | public void initialize() {
60 | startTime = Timer.getFPGATimestamp();
61 | currentSpeed = 0;
62 | acceleration = speedSupplier.get() / time;
63 | }
64 |
65 | /**
66 | * Calculate the speed and moves the subsystem.
67 | */
68 | @Override
69 | public void execute() {
70 | currentSpeed = (Timer.getFPGATimestamp() - startTime) * acceleration;
71 | if (Math.abs(currentSpeed) > Math.abs(speedSupplier.get()))
72 | currentSpeed = speedSupplier.get();
73 |
74 | subsystem.move(currentSpeed);
75 | }
76 |
77 | @Override
78 | public void end(boolean interrupted) {
79 | subsystem.stop();
80 | }
81 |
82 | @Override
83 | public boolean isFinished() {
84 | return super.isFinished() || currentSpeed == speedSupplier.get();
85 | }
86 | }
87 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/MoveGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands;
2 |
3 |
4 | import com.spikes2212.command.genericsubsystem.GenericSubsystem;
5 | import edu.wpi.first.wpilibj2.command.Command;
6 |
7 | import java.util.function.Supplier;
8 |
9 | /**
10 | * This command moves a {@link GenericSubsystem} until it can't move anymore.
11 | *
12 | * @author Yuval Levy
13 | * @see GenericSubsystem
14 | */
15 | public class MoveGenericSubsystem extends Command {
16 |
17 | protected final GenericSubsystem subsystem;
18 | protected final Supplier speedSupplier;
19 |
20 | /**
21 | * This constructs a new {@link MoveGenericSubsystem} command using the
22 | * {@link GenericSubsystem} this command operates on and a supplier supplying the
23 | * speed the {@link GenericSubsystem} should move with.
24 | *
25 | * @param subsystem the {@link GenericSubsystem} this command should move.
26 | * @param speedSupplier a Double {@link Supplier} supplying the speed this subsystem
27 | * should be moved with. Must only supply values between -1 and 1.
28 | */
29 | public MoveGenericSubsystem(GenericSubsystem subsystem, Supplier speedSupplier) {
30 | addRequirements(subsystem);
31 | this.subsystem = subsystem;
32 | this.speedSupplier = speedSupplier;
33 | }
34 |
35 | public MoveGenericSubsystem(GenericSubsystem subsystem, double speedSupplier) {
36 | this(subsystem, () -> speedSupplier);
37 | }
38 |
39 | @Override
40 | public void execute() {
41 | subsystem.move(speedSupplier.get());
42 | }
43 |
44 | @Override
45 | public void end(boolean interrupted) {
46 | subsystem.stop();
47 | }
48 |
49 | @Override
50 | public boolean isFinished() {
51 | return !subsystem.canMove(speedSupplier.get());
52 | }
53 | }
54 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/MoveGenericSubsystemWithPID.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands;
2 |
3 | import com.spikes2212.command.genericsubsystem.GenericSubsystem;
4 | import com.spikes2212.control.FeedForwardController;
5 | import com.spikes2212.control.FeedForwardSettings;
6 | import com.spikes2212.control.PIDSettings;
7 | import edu.wpi.first.math.controller.PIDController;
8 | import edu.wpi.first.wpilibj.Timer;
9 | import edu.wpi.first.wpilibj2.command.Command;
10 |
11 | import java.util.function.Supplier;
12 |
13 | /**
14 | * This command moves a {@link GenericSubsystem} according to a {@link Supplier}
15 | * or a constant speed until it reaches its target or can't move anymore.
16 | *
17 | * @author Yuval Levy
18 | * @see GenericSubsystem
19 | */
20 | public class MoveGenericSubsystemWithPID extends Command {
21 |
22 | protected final GenericSubsystem subsystem;
23 | protected final Supplier source;
24 | protected final PIDSettings pidSettings;
25 | protected final FeedForwardSettings feedForwardSettings;
26 | protected final Supplier setpoint;
27 | protected final Supplier acceleration;
28 |
29 | /**
30 | * An object that makes the necessary calculations for the PID control loop.
31 | */
32 | protected final PIDController pidController;
33 |
34 | /**
35 | * An object that makes the necessary calculations for the feed forward control loop.
36 | */
37 | protected final FeedForwardController feedForwardController;
38 |
39 | /**
40 | * The last time the subsystem didn't reach the target.
41 | */
42 | private double lastTimeNotOnTarget;
43 |
44 | /**
45 | * Constructs a new {@link MoveGenericSubsystemWithPID} command that moves the given
46 | * {@link GenericSubsystem} towards a setpoint given from a Double {@link Supplier}.
47 | *
48 | * @param subsystem the subsystem this command operates on
49 | * @param setpoint the Double {@link Supplier} supplying the setpoint
50 | * @param source the Double {@link Supplier} supplying the current position
51 | * @param acceleration the Double {@link Supplier} supplying the acceleration
52 | * @param pidSettings the pid constants used for calculating the move value for each iteration
53 | * @param feedForwardSettings the feed forward constants used for calculating the move value
54 | */
55 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, Supplier setpoint, Supplier source,
56 | Supplier acceleration, PIDSettings pidSettings,
57 | FeedForwardSettings feedForwardSettings) {
58 | addRequirements(subsystem);
59 | this.subsystem = subsystem;
60 | this.pidSettings = pidSettings;
61 | this.feedForwardSettings = feedForwardSettings;
62 | this.setpoint = setpoint;
63 | this.acceleration = acceleration;
64 | this.source = source;
65 | this.feedForwardController = new FeedForwardController(feedForwardSettings.getkS(), feedForwardSettings.getkV(),
66 | feedForwardSettings.getkA(), feedForwardSettings.getkG(), feedForwardSettings.getControlMode());
67 | this.pidController = new PIDController(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
68 | }
69 |
70 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, double setpoint, double source,
71 | Supplier acceleration, PIDSettings pidSettings,
72 | FeedForwardSettings feedForwardSettings) {
73 | this(subsystem, () -> setpoint, () -> source, acceleration, pidSettings, feedForwardSettings);
74 | }
75 |
76 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, Supplier setpoint, Supplier source,
77 | PIDSettings pidSettings) {
78 | this(subsystem, setpoint, source, () -> 0.0, pidSettings, FeedForwardSettings.EMPTY_FF_SETTINGS);
79 | }
80 |
81 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, double setpoint, double source,
82 | PIDSettings pidSettings) {
83 | this(subsystem, () -> setpoint, () -> source, pidSettings);
84 | }
85 |
86 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, Supplier setpoint, Supplier source,
87 | PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
88 | this(subsystem, setpoint, source, () -> 0.0, pidSettings, feedForwardSettings);
89 | }
90 |
91 | public MoveGenericSubsystemWithPID(GenericSubsystem subsystem, double setpoint, double source,
92 | PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
93 | this(subsystem, () -> setpoint, () -> source, () -> 0.0, pidSettings, feedForwardSettings);
94 | }
95 |
96 | protected double calculatePIDAndFFValues() {
97 | pidController.setTolerance(pidSettings.getTolerance());
98 | pidController.setPID(pidSettings.getkP(), pidSettings.getkI(), pidSettings.getkD());
99 | pidController.setIZone(pidSettings.getIZone());
100 | feedForwardController.setGains(feedForwardSettings);
101 |
102 | double pidValue = pidController.calculate(source.get(), setpoint.get());
103 | double svagValue = feedForwardController.calculate(source.get(), setpoint.get(), acceleration.get());
104 | return pidValue + svagValue;
105 | }
106 |
107 | @Override
108 | public void execute() {
109 | subsystem.move(calculatePIDAndFFValues());
110 | }
111 |
112 | @Override
113 | public void end(boolean interrupted) {
114 | subsystem.stop();
115 | }
116 |
117 | @Override
118 | public boolean isFinished() {
119 | if (!pidController.atSetpoint()) {
120 | lastTimeNotOnTarget = Timer.getFPGATimestamp();
121 | }
122 |
123 | return Timer.getFPGATimestamp() - lastTimeNotOnTarget >= pidSettings.getWaitTime();
124 | }
125 | }
126 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/MoveGenericSubsystemWithPIDForSpeed.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands;
2 |
3 | import com.spikes2212.command.genericsubsystem.GenericSubsystem;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 |
7 | import java.util.function.Supplier;
8 |
9 | /**
10 | * This command moves a {@link GenericSubsystem} according to a {@link Supplier} so it will reach a certain speed.
11 | *
12 | * @author Ofri Rosenbaum
13 | * @see MoveGenericSubsystemWithPID
14 | */
15 | @Deprecated(forRemoval = true, since = "2025")
16 | public class MoveGenericSubsystemWithPIDForSpeed extends MoveGenericSubsystemWithPID {
17 |
18 | public MoveGenericSubsystemWithPIDForSpeed(GenericSubsystem subsystem, Supplier targetVelocity,
19 | Supplier source, PIDSettings pidSettings,
20 | FeedForwardSettings feedForwardSettings) {
21 | super(subsystem, targetVelocity, source, pidSettings, feedForwardSettings);
22 | }
23 |
24 | public MoveGenericSubsystemWithPIDForSpeed(GenericSubsystem subsystem, double targetVelocity, double source,
25 | PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
26 | super(subsystem, targetVelocity, source, pidSettings, feedForwardSettings);
27 | }
28 |
29 | public MoveGenericSubsystemWithPIDForSpeed(GenericSubsystem subsystem, Supplier targetVelocity,
30 | Supplier source, PIDSettings pidSettings) {
31 | super(subsystem, targetVelocity, source, pidSettings);
32 | }
33 |
34 | public MoveGenericSubsystemWithPIDForSpeed(GenericSubsystem subsystem, double targetVelocity, double source,
35 | PIDSettings pidSettings) {
36 | super(subsystem, targetVelocity, source, pidSettings);
37 | }
38 |
39 | @Override
40 | public void execute() {
41 | subsystem.move(subsystem.getSpeed() + calculatePIDAndFFValues());
42 | }
43 | }
44 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/smartmotorcontrollergenericsubsystem/MoveSmartMotorControllerGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands.smartmotorcontrollergenericsubsystem;
2 |
3 | import com.spikes2212.command.genericsubsystem.smartmotorcontrollersubsystem.SmartMotorControllerGenericSubsystem;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.util.UnifiedControlMode;
7 | import edu.wpi.first.wpilibj.Timer;
8 | import edu.wpi.first.wpilibj2.command.Command;
9 |
10 | import java.util.function.Supplier;
11 |
12 | /**
13 | * A command that moves a {@link SmartMotorControllerGenericSubsystem} using its master motor controller's control loops.
14 | *
15 | * @author Yoel Perman Brilliant
16 | * @see SmartMotorControllerGenericSubsystem
17 | */
18 | public class MoveSmartMotorControllerGenericSubsystem extends Command {
19 |
20 | /**
21 | * The {@link SmartMotorControllerGenericSubsystem} this command will run on.
22 | */
23 | protected final SmartMotorControllerGenericSubsystem subsystem;
24 |
25 | /**
26 | * The loop's PID constants.
27 | */
28 | protected final PIDSettings pidSettings;
29 |
30 | /**
31 | * The loop's feed forward gains.
32 | */
33 | protected final FeedForwardSettings feedForwardSettings;
34 |
35 | /**
36 | * The loop's control mode (e.g. voltage, velocity, position...).
37 | */
38 | protected final UnifiedControlMode controlMode;
39 |
40 | /**
41 | * The setpoint this command should bring the {@link SmartMotorControllerGenericSubsystem} to.
42 | */
43 | protected final Supplier setpoint;
44 |
45 | protected final Supplier acceleration;
46 |
47 | protected final boolean updatePeriodically;
48 |
49 | /**
50 | * The most recent timestamp on which the loop has not reached its target setpoint.
51 | */
52 | private double lastTimeNotOnTarget;
53 |
54 | /**
55 | * Constructs a new instance of {@link MoveSmartMotorControllerGenericSubsystem}.
56 | *
57 | * @param subsystem the {@link SmartMotorControllerGenericSubsystem} this command will run on
58 | * @param pidSettings the loop's PID constants
59 | * @param feedForwardSettings the loop's feed forward gains
60 | * @param controlMode the loop's control mode (e.g. voltage, velocity, position...)
61 | * @param setpoint the setpoint this command should bring the {@link SmartMotorControllerGenericSubsystem} to
62 | */
63 | public MoveSmartMotorControllerGenericSubsystem(SmartMotorControllerGenericSubsystem subsystem, PIDSettings pidSettings,
64 | FeedForwardSettings feedForwardSettings,
65 | UnifiedControlMode controlMode, Supplier setpoint,
66 | Supplier acceleration, boolean updatePeriodically) {
67 | addRequirements(subsystem);
68 | this.subsystem = subsystem;
69 | this.controlMode = controlMode;
70 | this.pidSettings = pidSettings;
71 | this.feedForwardSettings = feedForwardSettings;
72 | this.setpoint = setpoint;
73 | this.acceleration = acceleration;
74 | this.updatePeriodically = updatePeriodically;
75 | this.lastTimeNotOnTarget = 0;
76 | }
77 |
78 | public MoveSmartMotorControllerGenericSubsystem(SmartMotorControllerGenericSubsystem subsystem, PIDSettings pidSettings,
79 | FeedForwardSettings feedForwardSettings,
80 | UnifiedControlMode controlMode, Supplier setpoint,
81 | boolean updatePeriodically) {
82 | this(subsystem, pidSettings, feedForwardSettings, controlMode, setpoint, () -> 0.0, updatePeriodically);
83 | }
84 |
85 | /**
86 | * Configures the subsystem's control loops.
87 | */
88 | @Override
89 | public void initialize() {
90 | subsystem.configureLoop(pidSettings, feedForwardSettings);
91 | }
92 |
93 | /**
94 | * Updates any control loops running on the subsystem.
95 | */
96 | @Override
97 | public void execute() {
98 | subsystem.pidSet(controlMode, setpoint.get(), acceleration.get(), pidSettings, feedForwardSettings,
99 | updatePeriodically);
100 | }
101 |
102 | @Override
103 | public void end(boolean interrupted) {
104 | subsystem.finish();
105 | }
106 |
107 | /**
108 | * Checks if the subsystem has been at its target setpoint for longer than its allowed wait time.
109 | *
110 | * @return {@code true} if the command should finish running, {@code false} otherwise
111 | */
112 | @Override
113 | public boolean isFinished() {
114 | if (!subsystem.onTarget(controlMode, pidSettings.getTolerance(), setpoint.get())) {
115 | lastTimeNotOnTarget = Timer.getFPGATimestamp();
116 | }
117 | return Timer.getFPGATimestamp() - lastTimeNotOnTarget >= pidSettings.getWaitTime();
118 | }
119 | }
120 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/commands/smartmotorcontrollergenericsubsystem/MoveSmartMotorControllerSubsystemTrapezically.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.commands.smartmotorcontrollergenericsubsystem;
2 |
3 | import com.spikes2212.command.genericsubsystem.smartmotorcontrollersubsystem.SmartMotorControllerGenericSubsystem;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.control.TrapezoidProfileSettings;
7 | import com.spikes2212.util.UnifiedControlMode;
8 |
9 | import java.util.function.Supplier;
10 |
11 |
12 | /**
13 | * A command that moves a {@link SmartMotorControllerGenericSubsystem} by running a trapezoid profile on its
14 | * master's control loops.
15 | *
16 | * @author Yoel Perman Brilliant
17 | * @see SmartMotorControllerGenericSubsystem
18 | * @see MoveSmartMotorControllerGenericSubsystem
19 | */
20 | public class MoveSmartMotorControllerSubsystemTrapezically extends MoveSmartMotorControllerGenericSubsystem {
21 |
22 | /**
23 | * The loops' trapezoid profile configurations.
24 | */
25 | protected final TrapezoidProfileSettings trapezoidProfileSettings;
26 |
27 | /**
28 | * Constructs a new instance of {@link MoveSmartMotorControllerSubsystemTrapezically}.
29 | *
30 | * @param subsystem the {@link SmartMotorControllerGenericSubsystem} this command will run on
31 | * @param pidSettings the loop's PID constants
32 | * @param feedForwardSettings the loop's feed forward gains
33 | * @param setpoint the setpoint this command should bring the {@link SmartMotorControllerGenericSubsystem} to
34 | * @param trapezoidProfileSettings the trapezoid profile settings
35 | */
36 | public MoveSmartMotorControllerSubsystemTrapezically(SmartMotorControllerGenericSubsystem subsystem, PIDSettings pidSettings,
37 | FeedForwardSettings feedForwardSettings,
38 | Supplier setpoint,
39 | TrapezoidProfileSettings trapezoidProfileSettings,
40 | boolean updatePeriodically) {
41 | super(subsystem, pidSettings, feedForwardSettings, UnifiedControlMode.TRAPEZOID_PROFILE, setpoint, updatePeriodically);
42 | this.trapezoidProfileSettings = trapezoidProfileSettings;
43 | }
44 |
45 | @Override
46 | public void initialize() {
47 | subsystem.configureLoop(pidSettings, feedForwardSettings, trapezoidProfileSettings);
48 | }
49 |
50 | @Override
51 | public void execute() {
52 | subsystem.pidSet(controlMode, setpoint.get(), pidSettings, feedForwardSettings,
53 | trapezoidProfileSettings, updatePeriodically);
54 | }
55 | }
56 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/smartmotorcontrollersubsystem/SmartMotorControllerGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.smartmotorcontrollersubsystem;
2 |
3 | import com.spikes2212.command.genericsubsystem.MotoredGenericSubsystem;
4 | import com.spikes2212.control.FeedForwardSettings;
5 | import com.spikes2212.control.PIDSettings;
6 | import com.spikes2212.control.TrapezoidProfileSettings;
7 | import com.spikes2212.util.UnifiedControlMode;
8 | import com.spikes2212.util.smartmotorcontrollers.SmartMotorController;
9 | import edu.wpi.first.wpilibj2.command.Subsystem;
10 |
11 | import java.util.List;
12 |
13 | /**
14 | * A {@link Subsystem} that runs control loops on an applicable motor controller.
15 | *
16 | * @author Yoel Perman Brilliant
17 | */
18 | public class SmartMotorControllerGenericSubsystem extends MotoredGenericSubsystem {
19 |
20 | private final List extends SmartMotorController> motorControllers;
21 |
22 | public SmartMotorControllerGenericSubsystem(String namespaceName, SmartMotorController... motorControllers) {
23 | super(namespaceName, motorControllers);
24 | this.motorControllers = List.of(motorControllers);
25 | }
26 |
27 | /**
28 | * Configures the loop's PID constants.
29 | */
30 | public void configurePID(PIDSettings pidSettings) {
31 | motorControllers.forEach(smartMotorController -> smartMotorController.configurePID(pidSettings));
32 | }
33 |
34 | /**
35 | * Configures the loop's feed forward gains.
36 | */
37 | public void configureFF(FeedForwardSettings feedForwardSettings) {
38 | motorControllers.forEach(smartMotorController -> smartMotorController.configureFF(feedForwardSettings));
39 | }
40 |
41 | /**
42 | * Configures the loop's trapezoid profile settings.
43 | */
44 | public void configureTrapezoid(TrapezoidProfileSettings settings) {
45 | motorControllers.forEach(smartMotorController -> smartMotorController.configureTrapezoid(settings));
46 | }
47 |
48 | /**
49 | * Configures the loop's settings.
50 | */
51 | public void configureLoop(PIDSettings pidSettings, FeedForwardSettings feedForwardSettings,
52 | TrapezoidProfileSettings trapezoidProfileSettings) {
53 | configurePID(pidSettings);
54 | configureFF(feedForwardSettings);
55 | configureTrapezoid(trapezoidProfileSettings);
56 | }
57 |
58 | /**
59 | * Configures the loop's settings.
60 | */
61 | public void configureLoop(PIDSettings pidSettings, FeedForwardSettings feedForwardSettings) {
62 | configureLoop(pidSettings, feedForwardSettings, TrapezoidProfileSettings.EMPTY_TRAPEZOID_PROFILE_SETTINGS);
63 | }
64 |
65 | /**
66 | * Updates any control loops running on the motor controller.
67 | *
68 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
69 | * @param setpoint the loop's target setpoint
70 | * @param pidSettings the PID constants
71 | * @param feedForwardSettings the feed forward gains
72 | * @param trapezoidProfileSettings the trapezoid profile settings
73 | * @param updatePeriodically whether to update the loop's settings periodically
74 | */
75 | public void pidSet(UnifiedControlMode controlMode, double setpoint, PIDSettings pidSettings,
76 | FeedForwardSettings feedForwardSettings, TrapezoidProfileSettings trapezoidProfileSettings,
77 | boolean updatePeriodically) {
78 | motorControllers.forEach(motorController -> motorController.pidSet(controlMode, setpoint, pidSettings,
79 | feedForwardSettings, trapezoidProfileSettings, updatePeriodically));
80 | }
81 |
82 | /**
83 | * Updates any control loops running on the motor controller.
84 | *
85 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
86 | * @param setpoint the loop's target setpoint
87 | * @param acceleration the loop's target acceleration
88 | * @param pidSettings the PID constants
89 | * @param feedForwardSettings the feed forward gains
90 | * @param updatePeriodically whether to update the loop's settings periodically
91 | */
92 | public void pidSet(UnifiedControlMode controlMode, double setpoint, double acceleration, PIDSettings pidSettings,
93 | FeedForwardSettings feedForwardSettings, boolean updatePeriodically) {
94 | motorControllers.forEach(motorController -> motorController.pidSet(controlMode, setpoint, acceleration,
95 | pidSettings, feedForwardSettings, updatePeriodically));
96 | }
97 |
98 | /**
99 | * Updates any control loops running on the motor controller.
100 | *
101 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
102 | * @param setpoint the loop's target setpoint
103 | * @param pidSettings the PID constants
104 | * @param feedForwardSettings the feed forward gains
105 | * @param updatePeriodically whether to update the loop's settings periodically
106 | */
107 | public void pidSet(UnifiedControlMode controlMode, double setpoint, PIDSettings pidSettings,
108 | FeedForwardSettings feedForwardSettings, boolean updatePeriodically) {
109 | motorControllers.forEach(motorController -> motorController.pidSet(controlMode, setpoint, 0,
110 | pidSettings, feedForwardSettings, updatePeriodically));
111 | }
112 |
113 | /**
114 | * Stops any control loops running on the motor controller.
115 | */
116 | public void finish() {
117 | motorControllers.forEach(motorControllers -> motorController.stopMotor());
118 | }
119 |
120 | /**
121 | * Checks whether the loop is currently on the target setpoint.
122 | *
123 | * @param controlMode the loop's control type (e.g. voltage, velocity, position...)
124 | * @param tolerance the maximum difference from the target to still be considered on target
125 | * @param setpoint the wanted setpoint
126 | * @return {@code true} when on target setpoint, {@code false} otherwise
127 | */
128 | public boolean onTarget(UnifiedControlMode controlMode, double tolerance, double setpoint) {
129 | return motorControllers.stream().allMatch(motorController -> motorController.onTarget(controlMode, tolerance,
130 | setpoint));
131 | }
132 | }
133 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/smartmotorcontrollersubsystem/SparkGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.smartmotorcontrollersubsystem;
2 |
3 | import com.revrobotics.spark.SparkBase;
4 | import com.spikes2212.command.DashboardedSubsystem;
5 | import com.spikes2212.util.smartmotorcontrollers.SparkWrapper;
6 | import edu.wpi.first.wpilibj2.command.Subsystem;
7 |
8 | /**
9 | * A {@link Subsystem} which consists of a master {@link SparkBase} motor controller that runs control
10 | * loops and additional {@link SparkBase} motor controllers that follow it.
11 | *
12 | * @author Yoel Perman Brilliant
13 | * @see DashboardedSubsystem
14 | * @see SmartMotorControllerGenericSubsystem
15 | */
16 | @Deprecated(since = "2025", forRemoval = true)
17 | public class SparkGenericSubsystem extends SmartMotorControllerGenericSubsystem {
18 |
19 | /**
20 | * Constructs a new instance of {@link SparkGenericSubsystem}.
21 | *
22 | * @param namespaceName the name of the subsystem's namespace
23 | */
24 | public SparkGenericSubsystem(String namespaceName, SparkWrapper... sparkWrappers) {
25 | super(namespaceName, sparkWrappers);
26 | }
27 | }
28 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/command/genericsubsystem/smartmotorcontrollersubsystem/TalonFXGenericSubsystem.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.command.genericsubsystem.smartmotorcontrollersubsystem;
2 |
3 | import com.ctre.phoenix6.hardware.TalonFX;
4 | import com.spikes2212.command.DashboardedSubsystem;
5 | import com.spikes2212.util.smartmotorcontrollers.TalonFXWrapper;
6 | import edu.wpi.first.wpilibj2.command.Subsystem;
7 |
8 | /**
9 | * A {@link Subsystem} which consists of a master {@link TalonFX} motor controller that runs control
10 | * loops and additional {@link TalonFX} motor controllers that follow it.
11 | *
12 | * @author Netta Halamish
13 | * @see DashboardedSubsystem
14 | * @see SmartMotorControllerGenericSubsystem
15 | */
16 | @Deprecated(since = "2025", forRemoval = true)
17 | public class TalonFXGenericSubsystem extends SmartMotorControllerGenericSubsystem {
18 |
19 | /**
20 | * Constructs a new instance of {@link TalonFXGenericSubsystem}.
21 | *
22 | * @param namespaceName the name of the subsystem's namespace
23 | */
24 | public TalonFXGenericSubsystem(String namespaceName, TalonFXWrapper... talonFXWrappers) {
25 | super(namespaceName, talonFXWrappers);
26 | }
27 | }
28 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/FeedForwardController.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control;
2 |
3 | /**
4 | * @author Tuval Rivkinind Barlev
5 | */
6 | public class FeedForwardController {
7 |
8 | public enum ControlMode {
9 |
10 | LINEAR_POSITION, LINEAR_VELOCITY, ANGULAR_POSITION, ANGULAR_VELOCITY;
11 | }
12 |
13 | /**
14 | * The type of feed forward control to use.
15 | */
16 | private final ControlMode controlMode;
17 |
18 | /**
19 | * The static constant.
20 | */
21 | private double kS;
22 |
23 | /**
24 | * The velocity constant.
25 | */
26 | private double kV;
27 |
28 | /**
29 | * The acceleration constant.
30 | */
31 | private double kA;
32 |
33 | /**
34 | * The gravity constant.
35 | */
36 | private double kG;
37 |
38 | public FeedForwardController(double kS, double kV, double kA, double kG, ControlMode controlMode) {
39 | this.kS = kS;
40 | this.kV = kV;
41 | this.kA = kA;
42 | this.kG = kG;
43 | this.controlMode = controlMode;
44 | }
45 |
46 | public FeedForwardController(double kV, double kA, ControlMode controlMode) {
47 | this(0, kV, kA, 0, controlMode);
48 | }
49 |
50 | public FeedForwardController(double kS, double kV, double kA, ControlMode controlMode) {
51 | this(kS, kV, kA, 0, controlMode);
52 | }
53 |
54 | public FeedForwardController(FeedForwardSettings settings) {
55 | this(settings.getkS(), settings.getkV(), settings.getkA(), settings.getkG(), settings.getControlMode());
56 | }
57 |
58 | public void setGains(double kV, double kA) {
59 | this.kV = kV;
60 | this.kA = kA;
61 | }
62 |
63 | public void setGains(double kS, double kV, double kA) {
64 | this.kS = kS;
65 | this.kV = kV;
66 | this.kA = kA;
67 | }
68 |
69 | public void setGains(double kS, double kV, double kA, double kG) {
70 | this.kS = kS;
71 | this.kV = kV;
72 | this.kA = kA;
73 | this.kG = kG;
74 | }
75 |
76 | public void setGains(FeedForwardSettings feedForwardSettings) {
77 | setGains(feedForwardSettings.getkS(), feedForwardSettings.getkV(), feedForwardSettings.getkA(),
78 | feedForwardSettings.getkG());
79 | }
80 |
81 | public double getkS() {
82 | return kS;
83 | }
84 |
85 | public void setkS(double kS) {
86 | this.kS = kS;
87 | }
88 |
89 | public double getkV() {
90 | return kV;
91 | }
92 |
93 | public void setkV(double kV) {
94 | this.kV = kV;
95 | }
96 |
97 | public double getkA() {
98 | return kA;
99 | }
100 |
101 | public void setkA(double kA) {
102 | this.kA = kA;
103 | }
104 |
105 | public double getkG() {
106 | return kG;
107 | }
108 |
109 | public void setkG(double kG) {
110 | this.kG = kG;
111 | }
112 |
113 | public ControlMode getControlMode() {
114 | return controlMode;
115 | }
116 |
117 | /**
118 | * Calculates the desired output using a simple feed forward method.
119 | *
120 | * @param source the current state
121 | * @param setpoint the desired state
122 | * @param acceleration the desired acceleration
123 | * @return the desired output
124 | */
125 | public double calculate(double source, double setpoint, double acceleration) {
126 | double kSValue = 0;
127 | double kGValue = 0;
128 | switch (controlMode) {
129 | case LINEAR_POSITION -> {
130 | kSValue = kS * Math.signum(setpoint - source);
131 | kGValue = kG;
132 | }
133 | case LINEAR_VELOCITY -> {
134 | kSValue = kS * Math.signum(setpoint);
135 | kGValue = kG;
136 | }
137 | case ANGULAR_POSITION -> {
138 | kSValue = kS * Math.signum(setpoint - source);
139 | kGValue = kG * Math.cos(source);
140 | }
141 | case ANGULAR_VELOCITY -> {
142 | kSValue = kS * Math.signum(setpoint);
143 | kGValue = kG * Math.cos(source);
144 | }
145 | }
146 | return kSValue + kV * setpoint + kA * acceleration + kGValue;
147 | }
148 |
149 | public double calculate(double source, double setpoint) {
150 | return calculate(source, setpoint, 0);
151 | }
152 | }
153 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/FeedForwardSettings.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control;
2 |
3 | import java.util.function.Supplier;
4 |
5 | /**
6 | * The constants used in a FeedForward calculation.
7 | *
8 | * @author Tal Sitton
9 | */
10 | public class FeedForwardSettings {
11 |
12 | /**
13 | * Empty FeedForwardSettings, which effectively make the FeedForwardController do nothing.
14 | */
15 | public static final FeedForwardSettings EMPTY_FF_SETTINGS = new FeedForwardSettings(
16 | FeedForwardController.ControlMode.LINEAR_POSITION);
17 |
18 | /**
19 | * The applied control mode.
20 | */
21 | private final FeedForwardController.ControlMode controlMode;
22 |
23 | /**
24 | * The static constant.
25 | */
26 | private Supplier kS;
27 |
28 | /**
29 | * The velocity constant.
30 | */
31 | private Supplier kV;
32 |
33 | /**
34 | * The acceleration constant.
35 | */
36 | private Supplier kA;
37 |
38 | /**
39 | * The gravity constant.
40 | */
41 | private Supplier kG;
42 |
43 | public FeedForwardSettings(Supplier kS, Supplier kV, Supplier kA, Supplier kG,
44 | FeedForwardController.ControlMode controlMode) {
45 | this.kS = kS;
46 | this.kV = kV;
47 | this.kA = kA;
48 | this.kG = kG;
49 | this.controlMode = controlMode;
50 | }
51 |
52 | public FeedForwardSettings(Supplier kS, Supplier kV, Supplier kA,
53 | FeedForwardController.ControlMode controlMode) {
54 | this(kS, kV, kA, () -> 0.0, controlMode);
55 | }
56 |
57 | public FeedForwardSettings(Supplier kV, Supplier kA,
58 | FeedForwardController.ControlMode controlMode) {
59 | this(() -> 0.0, kV, kA, () -> 0.0, controlMode);
60 | }
61 |
62 | public FeedForwardSettings(double kS, double kV, double kA, FeedForwardController.ControlMode controlMode) {
63 | this(() -> kS, () -> kV, () -> kA, () -> 0.0, controlMode);
64 | }
65 |
66 | public FeedForwardSettings(double kV, double kA, FeedForwardController.ControlMode controlMode) {
67 | this(() -> 0.0, () -> kV, () -> kA, () -> 0.0, controlMode);
68 | }
69 |
70 | public FeedForwardSettings(double kS, double kV, double kA, double kG,
71 | FeedForwardController.ControlMode controlMode) {
72 | this(() -> kS, () -> kV, () -> kA, () -> kG, controlMode);
73 | }
74 |
75 | public FeedForwardSettings(FeedForwardController.ControlMode controlMode) {
76 | this(() -> 0.0, () -> 0.0, () -> 0.0, () -> 0.0, controlMode);
77 | }
78 |
79 | public double getkS() {
80 | return kS.get();
81 | }
82 |
83 | public void setkS(Supplier kS) {
84 | this.kS = kS;
85 | }
86 |
87 | public double getkV() {
88 | return kV.get();
89 | }
90 |
91 | public void setkV(Supplier kV) {
92 | this.kV = kV;
93 | }
94 |
95 | public double getkA() {
96 | return kA.get();
97 | }
98 |
99 | public void setkA(Supplier kA) {
100 | this.kA = kA;
101 | }
102 |
103 | public double getkG() {
104 | return kG.get();
105 | }
106 |
107 | public void setkG(Supplier kG) {
108 | this.kG = kG;
109 | }
110 |
111 | public FeedForwardController.ControlMode getControlMode() {
112 | return controlMode;
113 | }
114 | }
115 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/PIDSettings.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control;
2 |
3 | import java.util.function.Supplier;
4 |
5 | /**
6 | * The constants used in a PID calculation, as well as tolerance and loop wait time.
7 | *
8 | * @author Eran Goldshtein
9 | */
10 | public class PIDSettings {
11 |
12 | /**
13 | * Empty PIDSettings, which effectively make the PIDController do nothing.
14 | */
15 | public static final PIDSettings EMPTY_PID_SETTINGS = new PIDSettings(0, 0, 0, 0, 0, 0);
16 |
17 | /**
18 | * the proportional component of the PID settings.
19 | */
20 | private Supplier kP;
21 |
22 | /**
23 | * the integral component of the PID settings.
24 | */
25 | private Supplier kI;
26 |
27 | /**
28 | * the derivative component of the PID settings.
29 | */
30 | private Supplier kD;
31 |
32 | /**
33 | * the distance in which the integral component begins to work.
34 | */
35 | private Supplier iZone;
36 |
37 | /**
38 | * the acceptable distance from the target.
39 | */
40 | private Supplier tolerance;
41 |
42 | /**
43 | * the time required to stay on target.
44 | */
45 | private Supplier waitTime;
46 |
47 | public PIDSettings(Supplier kP, Supplier kI, Supplier kD, Supplier iZone,
48 | Supplier tolerance, Supplier waitTime) {
49 | this.kP = kP;
50 | this.kI = kI;
51 | this.kD = kD;
52 | this.iZone = iZone;
53 | this.tolerance = tolerance;
54 | this.waitTime = waitTime;
55 | }
56 |
57 | public PIDSettings(double kP, double tolerance, double waitTime) {
58 | this(kP, 0.0, 0.0, tolerance, 0.0, waitTime);
59 | }
60 |
61 | public PIDSettings(double kP, double kI, double kD, double iZone, double tolerance, double waitTime) {
62 | this(() -> kP, () -> kI, () -> kD, () -> iZone, () -> tolerance, () -> waitTime);
63 | }
64 |
65 | public PIDSettings(Supplier kP, Supplier tolerance, Supplier waitTime) {
66 | this(kP, () -> 0.0, () -> 0.0, () -> 0.0, tolerance, waitTime);
67 | }
68 |
69 | public double getkP() {
70 | return kP.get();
71 | }
72 |
73 | public void setkP(Supplier kP) {
74 | this.kP = kP;
75 | }
76 |
77 | public double getkI() {
78 | return kI.get();
79 | }
80 |
81 | public void setkI(Supplier kI) {
82 | this.kI = kI;
83 | }
84 |
85 | public double getkD() {
86 | return kD.get();
87 | }
88 |
89 | public void setkD(Supplier kD) {
90 | this.kD = kD;
91 | }
92 |
93 | public double getTolerance() {
94 | return tolerance.get();
95 | }
96 |
97 | public void setTolerance(Supplier tolerance) {
98 | this.tolerance = tolerance;
99 | }
100 |
101 | public double getIZone() {
102 | return iZone.get();
103 | }
104 |
105 | public void setIZone(Supplier iZone) {
106 | this.iZone = iZone;
107 | }
108 |
109 | public double getWaitTime() {
110 | return waitTime.get();
111 | }
112 |
113 | public void setWaitTime(Supplier waitTime) {
114 | this.waitTime = waitTime;
115 | }
116 | }
117 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/TrapezoidProfileSettings.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control;
2 |
3 | import java.util.function.Supplier;
4 |
5 | /**
6 | * A data class for trapezoid profile configurations.
7 | *
8 | * @author Yoel Perman Brilliant
9 | */
10 | public class TrapezoidProfileSettings {
11 |
12 | /**
13 | * Empty {@link TrapezoidProfileSettings}, which effectively make the trapezoid profile do nothing.
14 | */
15 | public static final TrapezoidProfileSettings EMPTY_TRAPEZOID_PROFILE_SETTINGS =
16 | new TrapezoidProfileSettings(0, 0, 0);
17 |
18 | private Supplier maxAcceleration;
19 | private Supplier maxVelocity;
20 |
21 | /**
22 | * The S curve of the acceleration phase. The scale and units change depending on the motor controller.
23 | */
24 | private Supplier curve;
25 |
26 | public TrapezoidProfileSettings(Supplier maxAcceleration, Supplier maxVelocity,
27 | Supplier curve) {
28 | this.maxAcceleration = maxAcceleration;
29 | this.maxVelocity = maxVelocity;
30 | this.curve = curve;
31 | }
32 |
33 | public TrapezoidProfileSettings(Supplier maxAcceleration, Supplier maxVelocity) {
34 | this(maxAcceleration, maxVelocity, () -> 0.0);
35 | }
36 |
37 | public TrapezoidProfileSettings(double maxAcceleration, double maxVelocity, double curve) {
38 | this(() -> maxAcceleration, () -> maxVelocity, () -> curve);
39 | }
40 |
41 | public TrapezoidProfileSettings(double maxAcceleration, double maxVelocity) {
42 | this(maxAcceleration, maxVelocity, 0);
43 | }
44 |
45 | public double getMaxAcceleration() {
46 | return maxAcceleration.get();
47 | }
48 |
49 | public void setMaxAcceleration(Supplier maxAcceleration) {
50 | this.maxAcceleration = maxAcceleration;
51 | }
52 |
53 | public double getMaxVelocity() {
54 | return maxVelocity.get();
55 | }
56 |
57 | public void setMaxVelocity(Supplier maxVelocity) {
58 | this.maxVelocity = maxVelocity;
59 | }
60 |
61 | public double getCurve() {
62 | return curve.get();
63 | }
64 |
65 | public void setCurve(Supplier curve) {
66 | this.curve = curve;
67 | }
68 | }
69 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/noise/ExponentialFilter.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control.noise;
2 |
3 | /**
4 | * A class that handles noise-filtering by controlling the speed of motors using an exponential filter.
5 | *
6 | * @author Simon Kharmatsky
7 | */
8 | public class ExponentialFilter implements NoiseFilter {
9 |
10 | private double w;
11 |
12 | private double previous;
13 |
14 | public ExponentialFilter(double w) {
15 | this.w = w;
16 | }
17 |
18 | @Override
19 | public double calculate(double measurement) {
20 | double calculation = w * measurement + (1 - w) * previous;
21 | previous = calculation;
22 | return calculation;
23 | }
24 | }
25 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/noise/NoiseFilter.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control.noise;
2 |
3 | /**
4 | * An interface which is implemented by classes that handle noise-filtering.
5 | *
6 | * @author Simon Kharmatsky
7 | */
8 | public interface NoiseFilter {
9 |
10 | /**
11 | * A noise-filtering calculation
12 | */
13 | double calculate(double measurement);
14 | }
15 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/noise/NoiseReducer.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control.noise;
2 |
3 | import java.util.function.Supplier;
4 |
5 | /**
6 | * @author Simon Kharmatsky
7 | */
8 | public class NoiseReducer implements Supplier {
9 |
10 | private Supplier source;
11 |
12 | private NoiseFilter filter;
13 |
14 | public NoiseReducer(Supplier source, NoiseFilter filter) {
15 | this.source = source;
16 | this.filter = filter;
17 | }
18 |
19 | @Override
20 | public Double get() {
21 | return filter.calculate(source.get());
22 | }
23 | }
24 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/control/noise/RunningAverageFilter.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.control.noise;
2 |
3 | /**
4 | * A class that handles noise-filtering by controlling the speed of motors using an average filter.
5 | *
6 | * @author Simon Kharmatsky
7 | */
8 | public class RunningAverageFilter implements NoiseFilter {
9 |
10 | private double sum = 0;
11 | private int count = 0;
12 |
13 | private void reset() {
14 | sum = 0;
15 | count = 0;
16 | }
17 |
18 | @Override
19 | public double calculate(double measurement) {
20 | if (Math.signum(sum) != Math.signum(measurement)) reset();
21 | sum += measurement;
22 | count++;
23 | return sum / count;
24 | }
25 | }
26 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/dashboard/ChildNamespace.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.dashboard;
2 |
3 | import edu.wpi.first.util.sendable.Sendable;
4 |
5 | import java.util.function.Supplier;
6 |
7 | /**
8 | * This class represents a "subdirectory" of another {@link Namespace} which can store values or other ChildNamespaces.
9 | */
10 | public class ChildNamespace extends RootNamespace {
11 |
12 | protected final Namespace parent;
13 | protected final String separator;
14 |
15 | public ChildNamespace(String name, Namespace parent) {
16 | super(name);
17 | this.parent = parent;
18 | separator = "/";
19 | }
20 |
21 | public ChildNamespace(String name, Namespace parent, String separator) {
22 | super(name);
23 | this.parent = parent;
24 | this.separator = separator;
25 | }
26 |
27 | @Override
28 | public Supplier addConstantDouble(String name, double value) {
29 | return parent.addConstantDouble(this.name + separator + name, value);
30 | }
31 |
32 | @Override
33 | public Supplier addConstantInt(String name, int value) {
34 | return parent.addConstantInt(this.name + separator + name, value);
35 | }
36 |
37 | @Override
38 | public Supplier addConstantString(String name, String value) {
39 | return parent.addConstantString(this.name + separator + name, value);
40 | }
41 |
42 | @Override
43 | public void putData(String key, Sendable value) {
44 | parent.putData(name + separator + key, value);
45 | }
46 |
47 | @Override
48 | public Sendable getSendable(String key) {
49 | return parent.getSendable(name + separator + key);
50 | }
51 |
52 | @Override
53 | public void putString(String key, Supplier value) {
54 | parent.putString(name + separator + key, value);
55 | }
56 |
57 | @Override
58 | public String getString(String key) {
59 | return parent.getString(name + separator + key);
60 | }
61 |
62 | @Override
63 | public void putNumber(String key, Supplier extends Number> value) {
64 | parent.putNumber(name + separator + key, value);
65 | }
66 |
67 | @Override
68 | public double getNumber(String key) {
69 | return parent.getNumber(name + separator + key);
70 | }
71 |
72 | @Override
73 | public void putBoolean(String key, Supplier value) {
74 | parent.putBoolean(name + separator + key, value);
75 | }
76 |
77 | @Override
78 | public boolean getBoolean(String key) {
79 | return parent.getBoolean(name + separator + key);
80 | }
81 | }
82 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/dashboard/RootNamespace.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.dashboard;
2 |
3 | import edu.wpi.first.networktables.NetworkTable;
4 | import edu.wpi.first.networktables.NetworkTableEntry;
5 | import edu.wpi.first.networktables.NetworkTableInstance;
6 | import edu.wpi.first.networktables.NetworkTableValue;
7 | import edu.wpi.first.util.sendable.Sendable;
8 | import edu.wpi.first.util.sendable.SendableRegistry;
9 | import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
10 |
11 | import java.util.HashMap;
12 | import java.util.Map;
13 | import java.util.function.Supplier;
14 |
15 | /**
16 | * This class represents a "root directory" in the namespace where other {@link ChildNamespace} and values can be saved.
17 | */
18 | public class RootNamespace implements Namespace {
19 |
20 | protected final Map> stringFields;
21 | protected final Map> numberFields;
22 | protected final Map> booleanFields;
23 | protected final NetworkTable table;
24 | protected final String name;
25 |
26 | private final Map tablesToData;
27 |
28 | public RootNamespace(String name) {
29 | this.name = name;
30 | NetworkTableInstance inst = NetworkTableInstance.getDefault();
31 | this.table = inst.getTable(this.name);
32 | stringFields = new HashMap<>();
33 | numberFields = new HashMap<>();
34 | booleanFields = new HashMap<>();
35 | tablesToData = new HashMap<>();
36 | }
37 |
38 | @Override
39 | public Supplier addConstantDouble(String name, double value) {
40 | NetworkTableEntry entry = table.getEntry(name);
41 | if (!table.containsKey(name)) {
42 | entry.setDouble(value);
43 | entry.setPersistent();
44 | }
45 | return () -> entry.getDouble(value);
46 | }
47 |
48 | @Override
49 | public Supplier addConstantInt(String name, int value) {
50 | NetworkTableEntry entry = table.getEntry(name);
51 | if (!table.containsKey(name)) {
52 | entry.setNumber(value);
53 | entry.setPersistent();
54 | }
55 | return () -> entry.getNumber(value).intValue();
56 | }
57 |
58 | @Override
59 | public Supplier addConstantString(String name, String value) {
60 | NetworkTableEntry entry = table.getEntry(name);
61 | if (!table.containsKey(name)) {
62 | entry.setString(value);
63 | entry.setPersistent();
64 | }
65 | return () -> entry.getString(value);
66 | }
67 |
68 | @Override
69 | public ChildNamespace addChild(String name) {
70 | return new ChildNamespace(name, this);
71 | }
72 |
73 | @Override
74 | public void putData(String key, Sendable value) {
75 | Sendable sddata = tablesToData.get(key);
76 | if (sddata == null || sddata != value) {
77 | tablesToData.put(key, value);
78 | NetworkTable dataTable = table.getSubTable(key);
79 | SendableBuilderImpl builder = new SendableBuilderImpl();
80 | builder.setTable(dataTable);
81 | SendableRegistry.publish(value, builder);
82 | builder.startListeners();
83 | dataTable.getEntry(".name").setString(key);
84 | }
85 | }
86 |
87 | @Override
88 | public Sendable getSendable(String key) {
89 | NetworkTableEntry entry = this.table.getEntry(key);
90 | NetworkTableValue value = entry.getValue();
91 | return (Sendable) value.getValue();
92 | }
93 |
94 | @Override
95 | public void putString(String key, Supplier value) {
96 | remove(key);
97 | NetworkTableEntry entry = this.table.getEntry(key);
98 | entry.setString(value.get());
99 | stringFields.put(key, value);
100 | }
101 |
102 | @Override
103 | public String getString(String key) {
104 | NetworkTableEntry entry = this.table.getEntry(key);
105 | NetworkTableValue value = entry.getValue();
106 | return value.getString();
107 | }
108 |
109 | @Override
110 | public void putNumber(String key, Supplier extends Number> value) {
111 | remove(key);
112 | NetworkTableEntry entry = this.table.getEntry(key);
113 | entry.setNumber(value.get());
114 | numberFields.put(key, value);
115 | }
116 |
117 | @Override
118 | public double getNumber(String key) {
119 | NetworkTableEntry entry = this.table.getEntry(key);
120 | NetworkTableValue value = entry.getValue();
121 | return value.getDouble();
122 | }
123 |
124 | @Override
125 | public void putBoolean(String key, Supplier value) {
126 | remove(key);
127 | NetworkTableEntry entry = this.table.getEntry(key);
128 | entry.setBoolean(value.get());
129 | booleanFields.put(key, value);
130 | }
131 |
132 | @Override
133 | public boolean getBoolean(String key) {
134 | NetworkTableEntry entry = this.table.getEntry(key);
135 | NetworkTableValue value = entry.getValue();
136 | return value.getBoolean();
137 | }
138 |
139 | public void remove(String name) {
140 | stringFields.remove(name);
141 | numberFields.remove(name);
142 | booleanFields.remove(name);
143 | }
144 |
145 | @Override
146 | public void update() {
147 | updateBoolean();
148 | updateNumber();
149 | updateString();
150 | updateSendable();
151 | }
152 |
153 | private void updateString() {
154 | for (Map.Entry> map : stringFields.entrySet()) {
155 | NetworkTableEntry entry = this.table.getEntry(map.getKey());
156 | entry.setString(map.getValue().get());
157 | }
158 | }
159 |
160 | private void updateNumber() {
161 | for (Map.Entry> map : numberFields.entrySet()) {
162 | NetworkTableEntry entry = this.table.getEntry(map.getKey());
163 | entry.setNumber(map.getValue().get());
164 | }
165 | }
166 |
167 | private void updateBoolean() {
168 | for (Map.Entry> map : booleanFields.entrySet()) {
169 | NetworkTableEntry entry = this.table.getEntry(map.getKey());
170 | entry.setBoolean(map.getValue().get());
171 | }
172 | }
173 |
174 | private void updateSendable() {
175 | for (Sendable data : tablesToData.values()) {
176 | SendableRegistry.update(data);
177 | }
178 | }
179 | }
180 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/dashboard/SpikesLogger.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.dashboard;
2 |
3 | import edu.wpi.first.networktables.NetworkTable;
4 | import edu.wpi.first.wpilibj2.command.Command;
5 | import edu.wpi.first.wpilibj2.command.InstantCommand;
6 |
7 | import java.time.LocalTime;
8 |
9 | /**
10 | * A logger class meant to be used with the SpikesLogger desktop app
11 | * to log values from the robot to a computer in real-time.
12 | * Uses a {@link NetworkTable} to communicate with the computer.
13 | *
14 | * @author TzintzeneT
15 | */
16 | public class SpikesLogger extends RootNamespace {
17 |
18 | private static final String DEFAULT_NAME = "SpikesLogger";
19 | private static final String DEFAULT_KEY = "output";
20 |
21 | /**
22 | * NetworkTables key to use for the output.
23 | */
24 | private final String key;
25 |
26 | /**
27 | * Creates a SpikesLogger instance with custom name and key for the output location.
28 | */
29 | public SpikesLogger(String name, String key) {
30 | super(name);
31 | this.key = key;
32 | }
33 |
34 | /**
35 | * Creates a default SpikesLogger instance with a custom key (name = "SpikesLogger").
36 | */
37 | public SpikesLogger(String key) {
38 | this(DEFAULT_NAME, key);
39 | }
40 |
41 | /**
42 | * Creates a default SpikesLogger instance (name = "SpikesLogger", key = "output").
43 | */
44 | public SpikesLogger() {
45 | this(DEFAULT_NAME, DEFAULT_KEY);
46 | }
47 |
48 | /**
49 | * Logs the provided output to the NetworkTables and the SpikesLogger app.
50 | *
51 | * @param output the data to be logged
52 | */
53 | public void log(T output) {
54 | putString(key, output == null ? "null" : output.toString());
55 | }
56 |
57 | /**
58 | * Logs the provided output with a timestamp to the NetworkTables and the SpikesLogger app.
59 | *
60 | * @param output the data to be logged
61 | */
62 | public void logWithTimestamp(T output) {
63 | log(LocalTime.now() + ": " + output);
64 | }
65 |
66 | /**
67 | * Returns a command that logs the provided output to the NetworkTables and the SpikesLogger app.
68 | *
69 | * @param output the data to be logged
70 | * @return a command that logs the output
71 | */
72 | public Command logCommand(T output) {
73 | return new InstantCommand(() -> log(output));
74 | }
75 |
76 | /**
77 | * Returns a command that logs the provided output with a timestamp to the NetworkTables and the SpikesLogger app.
78 | *
79 | * @param output the data to be logged
80 | * @return a command that logs the output
81 | */
82 | public Command logWithTimestampCommand(T output) {
83 | return new InstantCommand(() -> logWithTimestamp(output));
84 | }
85 | }
86 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/OdometryHandler.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.path;
2 |
3 | import edu.wpi.first.math.geometry.Pose2d;
4 | import edu.wpi.first.math.geometry.Rotation2d;
5 | import edu.wpi.first.math.geometry.Translation2d;
6 | import edu.wpi.first.math.geometry.Twist2d;
7 |
8 | import java.util.function.Supplier;
9 |
10 | /**
11 | * A class which uses encoders to find the progress of a robot between discrete times.
12 | *
13 | * The calculate method should be called repeatedly, otherwise your robot's position
14 | * would not be recalculated, and therefore will be substantially inaccurate.
15 | */
16 | @Deprecated(since = "2025", forRemoval = true)
17 | public class OdometryHandler {
18 |
19 | private Supplier leftPosition, rightPosition;
20 | private Supplier yaw;
21 | private double lastLeftPosition = 0, lastRightPosition = 0, lastYaw = 0;
22 | private Pose2d pose;
23 |
24 | /**
25 | * creates a new {@link OdometryHandler} object, with given parameters
26 | *
27 | * @param leftPosition the left position supplier
28 | * @param rightPosition the right position supplier
29 | * @param angleSupplier the angle supplier
30 | * @param x the initial x coordinate
31 | * @param y the initial y coordinate
32 | */
33 | public OdometryHandler(Supplier leftPosition, Supplier rightPosition,
34 | Supplier angleSupplier, double x, double y) {
35 | this.leftPosition = leftPosition;
36 | this.rightPosition = rightPosition;
37 | this.yaw = angleSupplier;
38 | pose = new Pose2d(new Translation2d(x, y), Rotation2d.fromDegrees(yaw.get()));
39 | }
40 |
41 | public void calculate() {
42 | double leftPosition = this.leftPosition.get();
43 | double rightPosition = this.rightPosition.get();
44 | double yaw = this.yaw.get();
45 | double deltaLeftDistance = leftPosition - lastLeftPosition;
46 | double deltaRightDistance = rightPosition - lastRightPosition;
47 | double deltaYaw = yaw - lastYaw;
48 |
49 | double averageDeltaDistance = (deltaLeftDistance + deltaRightDistance) / 2.0;
50 | Rotation2d angle = Rotation2d.fromDegrees(deltaYaw);
51 |
52 | lastYaw = yaw;
53 | lastLeftPosition = leftPosition;
54 | lastRightPosition = rightPosition;
55 |
56 | Pose2d newPose = pose.exp(
57 | new Twist2d(averageDeltaDistance, 0.0, angle.getRadians()));
58 |
59 | pose = new Pose2d(newPose.getTranslation(), Rotation2d.fromDegrees(yaw));
60 | }
61 |
62 | public void set(double x, double y) {
63 | this.pose = new Pose2d(new Translation2d(x, y), new Rotation2d(yaw.get()));
64 | this.lastLeftPosition = 0;
65 | this.lastRightPosition = 0;
66 | }
67 |
68 | /**
69 | * @return the robot's current x coordinate
70 | */
71 | public double getX() {
72 | return pose.getTranslation().getX();
73 | }
74 |
75 | /**
76 | * @return the robot's current y coordinate
77 | */
78 | public double getY() {
79 | return pose.getTranslation().getY();
80 | }
81 |
82 | /**
83 | * @return the robot's current angle
84 | */
85 | public double getYaw() {
86 | return yaw.get();
87 | }
88 |
89 | /**
90 | * @return robot's coordinates as a {@link Waypoint} instance
91 | */
92 | public Waypoint getWaypoint() {
93 | return new Waypoint(getY(), getX());
94 | }
95 | }
96 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/Paths.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.path;
2 |
3 | import edu.wpi.first.wpilibj.Filesystem;
4 |
5 | import java.io.BufferedWriter;
6 | import java.io.IOException;
7 | import java.nio.charset.StandardCharsets;
8 | import java.nio.file.Files;
9 | import java.nio.file.Path;
10 | import java.util.ArrayList;
11 | import java.util.Arrays;
12 | import java.util.List;
13 | @Deprecated(since = "2025", forRemoval = true)
14 | public class Paths {
15 |
16 | /**
17 | * @param spacing the distance between two path filled in between path given as parameters
18 | * @param smoothWeight how smooth to make the path, should be about 0.75 to 0.98
19 | * @param tolerance the smoothing tolerance
20 | * @param maxVelocity the robot's maximum velocity
21 | * @param turningConstant speed constant at curves (the higher it is, the faster you turn)
22 | * @param maxAcceleration the robot's maximum acceleration
23 | * @param path the initial points on the path. Apart from the edges, non of the points are guaranteed
24 | * to be on the final path
25 | * @return the generated path
26 | */
27 | public static List generate(List path, double spacing, double smoothWeight, double tolerance,
28 | double maxVelocity, double turningConstant, double maxAcceleration) {
29 | List points = new ArrayList<>(path);
30 | fill(points, spacing);
31 | smooth(points, smoothWeight, tolerance);
32 | calculateDistances(points);
33 | calculateCurvatures(points);
34 | calculateMaxVelocities(points, maxVelocity, turningConstant);
35 | smoothVelocities(points, maxAcceleration);
36 | return points;
37 | }
38 |
39 | /**
40 | * @param spacing the distance between two path filled in between path given as parameters
41 | * @param smoothWeight how smooth to make the path, should be about 0.75 to 0.98
42 | * @param tolerance the smoothing tolerance
43 | * @param maxVelocity the robot's maximum velocity
44 | * @param turningConstant speed constant at curves (the higher it is, the faster you turn)
45 | * @param maxAcceleration the robot's maximum acceleration
46 | * @param path the initial points on the path. Apart from the edges, non of the points are guaranteed
47 | * to be on the final path
48 | * @return the generated path
49 | */
50 | public static List generate(double spacing, double smoothWeight, double tolerance, double maxVelocity,
51 | double turningConstant, double maxAcceleration, Waypoint... path) {
52 | return generate(Arrays.asList(path), spacing, smoothWeight, tolerance, maxVelocity, turningConstant,
53 | maxAcceleration);
54 | }
55 |
56 | private static void fill(List path, double spacing) {
57 | for (int i = 0; i < path.size() - 1; i++) {
58 | Waypoint startPoint = path.get(i);
59 | double length = path.get(i).distance(path.get(i + 1));
60 | int pathThatFit = (int) (length / spacing);
61 | Waypoint vector = new Waypoint((path.get(i + 1).getX() - path.get(i).getX()) * (spacing / length),
62 | (path.get(i + 1).getY() - path.get(i).getY()) * (spacing / length));
63 | for (int j = 0; j < pathThatFit; j++, i++) {
64 | path.add(i + 1, new Waypoint(
65 | startPoint.getX() + vector.getX() * (j + 1),
66 | startPoint.getY() + vector.getY() * (j + 1)
67 | ));
68 | }
69 | }
70 | }
71 |
72 | private static void smooth(List path, double smoothWeight, double tolerance) {
73 | double dataWeight = 1 - smoothWeight;
74 | double[][] newPath = new double[path.size()][2];
75 | for (int i = 0; i < path.size(); i++) {
76 | newPath[i] = path.get(i).toArray();
77 | }
78 | double[][] ogPath = Arrays.copyOf(newPath, newPath.length);
79 | double change = tolerance;
80 | while (change >= tolerance) {
81 | change = 0;
82 | for (int i = 1; i < newPath.length - 1; i++) {
83 | for (int j = 0; j < newPath[i].length; j++) {
84 | double aux = newPath[i][j];
85 | newPath[i][j] += dataWeight * (ogPath[i][j] - newPath[i][j])
86 | + smoothWeight * (newPath[i - 1][j] + newPath[i + 1][j] - 2 * newPath[i][j]);
87 | change += Math.abs(aux - newPath[i][j]);
88 | }
89 | }
90 | }
91 |
92 | for (int i = 0; i < newPath.length; i++) {
93 | path.set(i, new Waypoint(newPath[i][0], newPath[i][1]));
94 | }
95 | }
96 |
97 | private static void calculateDistances(List path) {
98 | double previousDistance = 0;
99 | path.get(0).setD(0);
100 | for (int i = 1; i < path.size(); i++) {
101 | previousDistance += path.get(i).distance(path.get(i - 1));
102 | path.get(i).setD(previousDistance);
103 | }
104 | }
105 |
106 | private static void calculateCurvatures(List path) {
107 | for (int i = 1; i < path.size() - 1; i++) {
108 | double x1 = path.get(i).getX();
109 | double y1 = path.get(i).getY();
110 | double x2 = path.get(i - 1).getX();
111 | double y2 = path.get(i - 1).getY();
112 | double x3 = path.get(i + 1).getX();
113 | double y3 = path.get(i + 1).getY();
114 | if (x1 == x2) x2 += 0.000001;
115 | if (y1 == y2 && y1 == y3) y2 += 0.000001;
116 | double k1 = 0.5 * (x1 * x1 + y1 * y1 - x2 * x2 - y2 * y2) / (x1 - x2);
117 | double k2 = (y1 - y2) / (x1 - x2);
118 | double b = 0.5 * (x2 * x2 - 2 * x2 * k1 + y2 * y2 - x3 * x3 + 2 * x3 * k1 - y3 * y3) / (x3 * k2 - y3 + y2 - x2 * k2);
119 | double a = k1 - k2 * b;
120 | double r = Math.sqrt((x1 - a) * (x1 - a) + (y1 - b) * (y1 - b));
121 | path.get(i).setCurvature(1 / r);
122 | }
123 | }
124 |
125 | private static void calculateMaxVelocities(List path, double maxVelocity, double turningConstant) {
126 | for (Waypoint p : path) {
127 | p.setV(Math.min(maxVelocity, turningConstant / p.getCurvature()));
128 | }
129 | }
130 |
131 | private static void smoothVelocities(List path, double maxAcceleration) {
132 | path.get(path.size() - 1).setV(0);
133 | for (int i = path.size() - 2; i >= 0; i--) {
134 | double distance = path.get(i).distance(path.get(i + 1));
135 | path.get(i).setV(Math.min(path.get(i).getV(),
136 | Math.sqrt(Math.pow(path.get(i + 1).getV(), 2) + 2 * maxAcceleration * distance)));
137 | }
138 | }
139 |
140 | /**
141 | * Exports the path to a CSV file with the following format:
142 | * x,y,velocity,distance,curvature.
143 | *
144 | * @param path the path to export
145 | * @param file the CSV file
146 | */
147 | public static void exportToCSV(List path, Path file) {
148 | try (BufferedWriter writer = Files.newBufferedWriter(file, StandardCharsets.US_ASCII)) {
149 | StringBuilder s = new StringBuilder("x,y,velocity,distance,curvature\n");
150 | for (Waypoint w : path) {
151 | s.append(w.getX()).append(",").append(w.getY()).append(",").append(w.getV()).append(",")
152 | .append(w.getD()).append(",").append(w.getCurvature()).append("\n");
153 | }
154 | writer.write(s.toString(), 0, s.length());
155 | } catch (IOException ioe) {
156 | ioe.printStackTrace();
157 | }
158 | }
159 |
160 | /**
161 | * Loads a path from the given csv file
162 | *
163 | * @param path the csv file to import from
164 | * @return the path
165 | */
166 | public static List loadFromCSV(Path path) {
167 | List waypoints = new ArrayList<>();
168 | try {
169 | List lines = Files.readAllLines(path);
170 | lines.remove(0);
171 | for (String line : lines) {
172 | String[] values = line.split(",");
173 | Waypoint point = new Waypoint(Double.parseDouble(values[0]),
174 | Double.parseDouble(values[1]));
175 | point.setV(Double.parseDouble(values[2]));
176 | point.setD(Double.parseDouble(values[3]));
177 | point.setCurvature(Double.parseDouble(values[4]));
178 | waypoints.add(point);
179 | }
180 | } catch (IOException ioe) {
181 | ioe.printStackTrace();
182 | }
183 | return waypoints;
184 | }
185 |
186 | public static List loadFromCSV(String name) {
187 | return loadFromCSV(java.nio.file.Paths.get(Filesystem.getDeployDirectory().toString(), name));
188 | }
189 | }
190 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/PurePursuitController.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.path;
2 |
3 | import java.util.List;
4 |
5 | /**
6 | * This class represents a PurePursuitController.
7 | * You should the getSpeeds method periodically.
8 | *
9 | * @author Tuval Rivking Barlev
10 | */
11 | @Deprecated(since = "2025", forRemoval = true)
12 | public class PurePursuitController {
13 |
14 | private OdometryHandler odometryHandler;
15 | private List path;
16 | private int lastClosestIndex = 0, lastLookaheadIndex = 0;
17 | private double lookaheadDistance;
18 | private double robotWidth;
19 |
20 | private RateLimiter rateLimiter;
21 |
22 | public PurePursuitController(OdometryHandler odometryHandler, List path, double lookaheadDistance,
23 | double maxRate, double robotWidth, double period) {
24 | this.odometryHandler = odometryHandler;
25 | this.path = path;
26 | this.lookaheadDistance = lookaheadDistance;
27 | this.robotWidth = robotWidth;
28 | this.rateLimiter = new RateLimiter(maxRate, period);
29 | }
30 |
31 | public PurePursuitController(OdometryHandler odometryHandler, List path, double lookaheadDistance,
32 | double maxRate, double robotWidth) {
33 | this(odometryHandler, path, lookaheadDistance, maxRate, robotWidth, 0.02);
34 | }
35 |
36 | public OdometryHandler getOdometryHandler() {
37 | return odometryHandler;
38 | }
39 |
40 | public void setOdometryHandler(OdometryHandler odometryHandler) {
41 | this.odometryHandler = odometryHandler;
42 | }
43 |
44 | public List getPath() {
45 | return path;
46 | }
47 |
48 | public void setPath(List path) {
49 | this.path = path;
50 | }
51 |
52 | public double getLookaheadDistance() {
53 | return lookaheadDistance;
54 | }
55 |
56 | public void setLookaheadDistance(double lookaheadDistance) {
57 | this.lookaheadDistance = lookaheadDistance;
58 | }
59 |
60 | private Waypoint closestPoint() {
61 | Waypoint robot = odometryHandler.getWaypoint();
62 | double minDistance = Double.POSITIVE_INFINITY, distance;
63 | int minIndex = lastClosestIndex;
64 | for (int i = lastClosestIndex; i < path.size(); i++) {
65 | if ((distance = path.get(i).distance(robot)) < minDistance) {
66 | minIndex = i;
67 | minDistance = distance;
68 | }
69 | }
70 | lastClosestIndex = minIndex;
71 | return path.get(minIndex);
72 | }
73 |
74 | private Waypoint getLookaheadPoint() {
75 | Waypoint robot = odometryHandler.getWaypoint();
76 | for (int i = lastLookaheadIndex; i < path.size() - 1; i++) {
77 | Waypoint segment = new Waypoint(path.get(i + 1).getX() - path.get(i).getX()
78 | , path.get(i + 1).getY() - path.get(i).getY());
79 | Waypoint robotToStart = new Waypoint(path.get(i).getX() - robot.getX()
80 | , path.get(i).getY() - robot.getY());
81 | double a = segment.getX() * segment.getX() + segment.getY() * segment.getY();
82 | double b = 2 * (robotToStart.getX() * segment.getX() + robotToStart.getY() * segment.getY());
83 | double c = robotToStart.getX() * robotToStart.getX() + robotToStart.getY() * robotToStart.getY()
84 | - lookaheadDistance * lookaheadDistance;
85 | double discriminant = b * b - 4 * a * c;
86 | if (discriminant >= 0) {
87 | discriminant = Math.sqrt(discriminant);
88 | double t1 = (-b - discriminant) / (2 * a);
89 | double t2 = (-b + discriminant) / (2 * a);
90 | if (t1 >= 0 && t1 <= 1) {
91 | lastLookaheadIndex = i;
92 | return new Waypoint(path.get(i).getX() + t1 * segment.getX(),
93 | path.get(i).getY() + t1 * segment.getY());
94 | }
95 | if (t2 >= 0 && t2 <= 1) {
96 | lastLookaheadIndex = i;
97 | return new Waypoint(path.get(i).getX() + t2 * segment.getX(),
98 | path.get(i).getY() + t2 * segment.getY());
99 | }
100 | }
101 | }
102 | return null;
103 | }
104 |
105 | private double pathCurvature() {
106 | Waypoint robot = odometryHandler.getWaypoint();
107 | Waypoint lookahead = getLookaheadPoint();
108 | if (lookahead == null) return Double.POSITIVE_INFINITY;
109 | double yaw = Math.toRadians(90 - odometryHandler.getYaw());
110 | double slope = Math.tan(yaw);
111 | double freeTerm = slope * robot.getX() - robot.getY();
112 | double x = Math.abs(-slope * lookahead.getX() + lookahead.getY() + freeTerm) /
113 | Math.sqrt(slope * slope + 1); //distance between lookahead point and robot line
114 | double side = Math.sin(yaw) * (lookahead.getX() - robot.getX()) -
115 | Math.cos(yaw) * (lookahead.getY() - robot.getY()); //uses cross product to determine side
116 | if (side == 0) return 0;
117 | return 2 * x / (lookaheadDistance * lookaheadDistance) * side / Math.abs(side);
118 | }
119 |
120 | /**
121 | * Returns the target speeds for left and right as an array.
122 | * Left speed at index 0, right speed at index 1.
123 | * The List has ended when the speeds become {@code Double.POSITIVE_INFINITY}.
124 | *
125 | * @return the target side speeds as an array
126 | */
127 | public double[] getTargetSpeeds() {
128 | double velocity = rateLimiter.calculate(closestPoint().getV());
129 | double pathCurvature = pathCurvature();
130 | return new double[]{velocity * (2 + pathCurvature * robotWidth) / 2,
131 | velocity * (2 - pathCurvature * robotWidth) / 2};
132 | }
133 |
134 | /**
135 | * Resets the PurePursuitController's local variables so it can be used again.
136 | * This method should be called right before you start running a path.
137 | */
138 | public void reset() {
139 | lastClosestIndex = 0;
140 | lastLookaheadIndex = 0;
141 | }
142 |
143 | /**
144 | * returns whether the PurePursuitController has finished following the path.
145 | *
146 | * @return whether the PurePursuitController has finished following the path
147 | */
148 | public boolean done() {
149 | return closestPoint().equals(path.get(path.size() - 1));
150 | }
151 | }
152 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/README.md:
--------------------------------------------------------------------------------
1 | ## Adaptive Pure Pursuit Controller
2 |
3 | This code is our implementation of an Adaptive Pure Pursuit Controller according to the specification of team [Dawgma 1712](https://www.chiefdelphi.com/t/paper-implementation-of-the-adaptive-pure-pursuit-controller/166552).
4 |
5 | Currently, we support only Tank drivetrains, and will be glad to accept contributions.
6 |
7 | Command bindings for this controller are located in `com.spikes2212.command.drivetrains.command`
8 |
9 | This package is deprecated and will be deleted in 2026.
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/RateLimiter.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.path;
2 |
3 | /**
4 | * This class is used to limit the rate of change of robot velocities,
5 | * it is used in {@link PurePursuitController} in order to achieve smoother acceleration.
6 | */
7 | @Deprecated(since = "2025", forRemoval = true)
8 | public class RateLimiter {
9 |
10 | private double maxAcceleration;
11 | private double period;
12 | private double lastVelocity = 0;
13 |
14 | public RateLimiter(double maxAcceleration, double period) {
15 | this.maxAcceleration = maxAcceleration;
16 | this.period = period;
17 | }
18 |
19 | private double clampRate(double rate) {
20 | double maxRate = getMaxChange();
21 | return Math.max(-maxRate, Math.min(maxRate, rate));
22 | }
23 |
24 | public double calculate(double targetVelocity) {
25 | lastVelocity = lastVelocity + clampRate(targetVelocity - lastVelocity);
26 | return lastVelocity;
27 | }
28 |
29 | public double getPeriod() {
30 | return period;
31 | }
32 |
33 | public void setPeriod(double period) {
34 | this.period = period;
35 | }
36 |
37 | public double getMaxChange() {
38 | return maxAcceleration * period;
39 | }
40 | }
41 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/path/Waypoint.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.path;
2 |
3 | /**
4 | * This class represents a point in 2d space, with additional fields used for path generation and following.
5 | *
6 | * @author Tuval Rivkind Barlev
7 | */
8 | @Deprecated(since = "2025", forRemoval = true)
9 | public class Waypoint {
10 |
11 | /**
12 | * The x coordinate.
13 | */
14 | private final double x;
15 |
16 | /**
17 | * The y coordinate.
18 | */
19 | private final double y;
20 |
21 | /**
22 | * The velocity at the given point (used for path following).
23 | */
24 | private double v;
25 |
26 | /**
27 | * The distance from the origin of the path along the path.
28 | */
29 | private double d;
30 |
31 | /**
32 | * The curvature of the path at the point.
33 | */
34 | private double curvature;
35 |
36 | public Waypoint(double x, double y) {
37 | this.x = x;
38 | this.y = y;
39 | }
40 |
41 | /**
42 | * @param point the point to calculate the distance from
43 | * @return the distance between the points
44 | */
45 | public double distance(Waypoint point) {
46 | return Math.sqrt((x - point.getX()) * (getX() - point.getX()) + (getY() - point.getY()) * (getY() - point.getY()));
47 | }
48 |
49 | public double getX() {
50 | return x;
51 | }
52 |
53 | public double getY() {
54 | return y;
55 | }
56 |
57 | public double getV() {
58 | return v;
59 | }
60 |
61 | void setV(double v) {
62 | this.v = v;
63 | }
64 |
65 | void setD(double distance) {
66 | this.d = distance;
67 | }
68 |
69 | public double getD() {
70 | return d;
71 | }
72 |
73 | /**
74 | * @return an array of the point's coordinates
75 | */
76 | public double[] toArray() {
77 | return new double[]{x, y};
78 | }
79 |
80 | public double getCurvature() {
81 | return curvature;
82 | }
83 |
84 | void setCurvature(double curvature) {
85 | this.curvature = curvature;
86 | }
87 |
88 | @Override
89 | public String toString() {
90 | return "x: " + x + " y: " + y;
91 | }
92 | }
93 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/state/ButtonLayout.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.state;
2 |
3 | import edu.wpi.first.wpilibj2.command.Command;
4 |
5 | import java.util.HashMap;
6 | import java.util.Map;
7 |
8 | @Deprecated(since = "2025", forRemoval = true)
9 | public abstract class ButtonLayout> {
10 |
11 | private Map buttons = new HashMap<>();
12 |
13 | public void addButton(T button, Command command) {
14 | buttons.put(button, command);
15 | }
16 |
17 | public Command getCommandForButton(T button) {
18 | return buttons.get(button);
19 | }
20 | }
21 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/state/LayoutManager.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.state;
2 |
3 | import edu.wpi.first.wpilibj2.command.Command;
4 | import edu.wpi.first.wpilibj2.command.ProxyCommand;
5 |
6 | import java.util.HashMap;
7 | import java.util.Map;
8 |
9 | @Deprecated(since = "2025", forRemoval = true)
10 | public abstract class LayoutManager, K extends Enum> {
11 |
12 | private Map> allLayouts = new HashMap<>();
13 | private ButtonLayout currentLayout;
14 |
15 | public void addLayout(T mode, ButtonLayout layout) {
16 | allLayouts.put(mode, layout);
17 | }
18 |
19 | public Command getCommandFor(K button) {
20 | return new ProxyCommand(() -> allLayouts.get(currentLayout).getCommandForButton(button));
21 | }
22 |
23 | public void setLayout(T layout) {
24 | currentLayout = allLayouts.get(layout);
25 | }
26 | }
27 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/state/StateMachine.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.state;
2 |
3 | import edu.wpi.first.wpilibj2.command.Command;
4 | import edu.wpi.first.wpilibj2.command.InstantCommand;
5 | import edu.wpi.first.wpilibj2.command.ProxyCommand;
6 |
7 | import java.util.HashMap;
8 | import java.util.Map;
9 |
10 | @Deprecated(since = "2025", forRemoval = true)
11 | public abstract class StateMachine> {
12 |
13 | private Map transformations;
14 | private T state;
15 |
16 | public StateMachine(T initialState) {
17 | setState(initialState);
18 | transformations = new HashMap<>();
19 | generateTransformations();
20 | }
21 |
22 | protected abstract void generateTransformations();
23 |
24 | protected void addTransformation(T state, Command command) {
25 | transformations.put(state, new InstantCommand(() -> setState(state)).andThen(command));
26 | }
27 |
28 | public Command getTransformationFor(T state) {
29 | return new ProxyCommand(transformations.get(state));
30 | }
31 |
32 | protected void setState(T state) {
33 | this.state = state;
34 | }
35 |
36 | public T getState() {
37 | return state;
38 | }
39 | }
40 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/AddressableLEDWrapper.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.wpilibj.AddressableLED;
4 | import edu.wpi.first.wpilibj.AddressableLEDBuffer;
5 |
6 | import java.awt.Color;
7 |
8 | /**
9 | * A class that handles the communication between a LED strip and the code.
10 | * This class still requires further testing and an update will be made as soon as testing is finished.
11 | *
12 | * @author Camellia Lami
13 | */
14 | public class AddressableLEDWrapper {
15 |
16 | /**
17 | * The controlled LED strip.
18 | */
19 | protected final AddressableLED led;
20 |
21 | /**
22 | * The controlled LED strip's data.
23 | */
24 | protected final AddressableLEDBuffer ledBuffer;
25 |
26 | public AddressableLEDWrapper(int ledPort, int numberOfLEDs) {
27 | this.led = new AddressableLED(ledPort);
28 | led.setLength(numberOfLEDs);
29 | this.ledBuffer = new AddressableLEDBuffer(numberOfLEDs);
30 | }
31 |
32 | /**
33 | * Sets the LED strip to a specific color.
34 | *
35 | * @param red the red value from 0 to 255
36 | * @param green the green value from 0 to 255
37 | * @param blue the blue value from 0 to 255
38 | */
39 | public void setStripColor(int red, int green, int blue) {
40 | setColorInRange(0, ledBuffer.getLength() - 1, red, green, blue);
41 | }
42 |
43 | /**
44 | * Sets the LED strip to a specific color.
45 | *
46 | * @param color the desired {@link Color}
47 | */
48 | public void setStripColor(Color color) {
49 | setStripColor(color.getRed(), color.getGreen(), color.getBlue());
50 | }
51 |
52 | /**
53 | * Turns off the strip.
54 | */
55 | public void turnOff() {
56 | setStripColor(0, 0, 0);
57 | }
58 |
59 | /**
60 | * Sets a certain range of LEDs to a specific color.
61 | *
62 | * @param start the first LED in the range
63 | * @param end the final LED in the range
64 | * @param red the red value from 0 to 255
65 | * @param green the green value from 0 to 255
66 | * @param blue the blue value from 0 to 255
67 | */
68 | public void setColorInRange(int start, int end, int red, int green, int blue) {
69 | for (int i = start; i <= end; i++) {
70 | ledBuffer.setRGB(i, red, green, blue);
71 | }
72 | }
73 |
74 | /**
75 | * Sets a certain range of LEDs to a specific color.
76 | *
77 | * @param start the first LED in the range
78 | * @param end the final LED in the range
79 | * @param color the desired {@link Color}
80 | */
81 | public void setColorInRange(int start, int end, Color color) {
82 | setColorInRange(start, end, color.getRed(), color.getGreen(), color.getBlue());
83 | }
84 |
85 | /**
86 | * Sets a specific LED to a specific color.
87 | *
88 | * @param index the index of the LED
89 | * @param red the red value from 0 to 255
90 | * @param green the green value from 0 to 255
91 | * @param blue the blue value from 0 to 255
92 | */
93 | public void setColorAt(int index, int red, int green, int blue) {
94 | ledBuffer.setRGB(index, red, green, blue);
95 | }
96 |
97 | /**
98 | * Sets a specific LED to a specific color.
99 | *
100 | * @param index the index of the LED
101 | * @param color the desired {@link Color}
102 | */
103 | public void setColorAt(int index, Color color) {
104 | ledBuffer.setRGB(index, color.getRed(), color.getGreen(), color.getBlue());
105 | }
106 |
107 | /**
108 | * Takes the buffer's data and applies it to the LED strip.
109 | * This method should be called periodically.
110 | */
111 | public void update() {
112 | led.setData(ledBuffer);
113 | }
114 |
115 | /**
116 | * Activates the LED strip.
117 | */
118 | public void enableStrip() {
119 | led.start();
120 | }
121 |
122 | /**
123 | * Deactivates the LED strip.
124 | */
125 | public void disableStrip() {
126 | led.stop();
127 | }
128 | }
129 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/BustedMotorControllerGroup.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
4 |
5 | import java.util.function.Supplier;
6 |
7 | /**
8 | * An extension of the {@code MotorControllerGroup} class that has the ability to add a correction to its speed.
9 | * Best used to correct deviation in the drivetrain.
10 | *
11 | * @author Yotam Yizhar
12 | */
13 | public class BustedMotorControllerGroup extends MotorControllerGroup {
14 |
15 | /**
16 | * The wanted amount to correct the {@code MotorControllerGroup} (range 0.1-1).
17 | */
18 | protected final Supplier correction;
19 |
20 | public BustedMotorControllerGroup(Supplier correction, MotorController... motorControllers) {
21 | super(motorControllers);
22 | this.correction = correction;
23 | }
24 |
25 | public BustedMotorControllerGroup(double correction, MotorController... motorControllers) {
26 | this(() -> correction, motorControllers);
27 | }
28 |
29 | @Override
30 | public void set(double speed) {
31 | super.set(speed * correction.get());
32 | }
33 | }
34 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/DPAD.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | /**
4 | * D-PAD values.
5 | *
6 | * @author Ofri Rosenbaum
7 | */
8 | public enum DPAD {
9 |
10 | UP(0),
11 | UPPER_RIGHT(45),
12 | RIGHT(90),
13 | LOWER_RIGHT(135),
14 | DOWN(180),
15 | LOWER_LEFT(225),
16 | LEFT(270),
17 | UPPER_LEFT(315);
18 |
19 | public final int value;
20 |
21 | DPAD(int value) {
22 | this.value = value;
23 | }
24 | }
25 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/Limelight.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.math.geometry.Pose3d;
4 | import edu.wpi.first.math.geometry.Rotation3d;
5 | import edu.wpi.first.math.geometry.Translation3d;
6 | import edu.wpi.first.networktables.NetworkTableEntry;
7 | import edu.wpi.first.networktables.NetworkTableInstance;
8 | import edu.wpi.first.networktables.NetworkTableValue;
9 |
10 | /**
11 | * A Wrapper for a Limelight camera.
12 | *
13 | * @author Yotam Yizhar
14 | */
15 | public class Limelight {
16 |
17 | public enum CamMode {
18 |
19 | VISION_PROCESSOR(0), DRIVER_CAMERA(1);
20 |
21 | private final int mode;
22 |
23 | CamMode(int mode) {
24 | this.mode = mode;
25 | }
26 |
27 | public int getCamMode() {
28 | return mode;
29 | }
30 | }
31 |
32 | public enum LedMode {
33 |
34 | DEFAULT(0), FORCE_OFF(1), FORCE_BLINK(2), FORCE_ON(3);
35 |
36 | private final int mode;
37 |
38 | LedMode(int mode) {
39 | this.mode = mode;
40 | }
41 |
42 | public int getLedMode() {
43 | return this.mode;
44 | }
45 | }
46 |
47 | private static final String DEFAULT_NAME = "limelight";
48 |
49 | protected static NetworkTableInstance table;
50 |
51 | private final String name;
52 |
53 | public Limelight(String limelightName) {
54 | this.name = limelightName;
55 | }
56 |
57 | public Limelight() {
58 | this(DEFAULT_NAME);
59 | }
60 |
61 | /**
62 | * Retrieves an entry from the Limelight's NetworkTable.
63 | *
64 | * @param key key for entry
65 | * @return the value of the given key's entry
66 | */
67 | public NetworkTableEntry getEntry(String key) {
68 | if (table == null) {
69 | table = NetworkTableInstance.getDefault();
70 | }
71 | return table.getTable(name).getEntry(key);
72 | }
73 |
74 | /**
75 | * Retrieves a value associated with a given key.
76 | *
77 | * @param key the key whose value should be retrieved
78 | * @return the value of the given key
79 | */
80 | public NetworkTableValue getValue(String key) {
81 | return getEntry(key).getValue();
82 | }
83 |
84 | /**
85 | * @return whether a target is detected by the limelight
86 | */
87 | public boolean hasTarget() {
88 | return getEntry("tv").getDouble(0) == 1;
89 | }
90 |
91 | /**
92 | * @return the current limelight's pipeline
93 | */
94 | public int getPipeline() {
95 | return (int) getEntry("getpipe").getNumber(0);
96 | }
97 |
98 | /**
99 | * Sets pipeline number (0-9 value).
100 | *
101 | * @param number pipeline number (0-9)
102 | */
103 | public void setPipeline(int number) {
104 | getEntry("pipeline").setNumber(number);
105 | }
106 |
107 | /**
108 | * @return the robot's {@link Pose3d} in field-space (works for april tags), or null if there is no target.
109 | * (0,0,0) is in the middle of the field.
110 | */
111 | public Pose3d getRobotPose() {
112 | double[] result = getEntry("botpose").getDoubleArray(new double[]{});
113 | if (getID() >= 0) {
114 | Translation3d translation3d = new Translation3d(result[0], result[1], result[2]);
115 | Rotation3d rotation3d = new Rotation3d(Math.toRadians(result[3]), Math.toRadians(result[4]), Math.toRadians(result[5]));
116 | return new Pose3d(translation3d, rotation3d);
117 | }
118 | return null;
119 | }
120 |
121 | /**
122 | * @return the ID of the primary april tag.
123 | */
124 | public long getID() {
125 | return getEntry("tid").getInteger(0);
126 | }
127 |
128 | /**
129 | * @return the horizontal offset from crosshair to target (-27 degrees to 27 degrees)
130 | */
131 | public double getHorizontalOffsetFromTargetInDegrees() {
132 | return getEntry("tx").getDouble(0.00);
133 | }
134 |
135 | /**
136 | * @return the raw horizontal offset from crosshair to target in pixels (-1 to 1)
137 | */
138 | public double getHorizontalOffsetFromTargetInPixels() {
139 | return getEntry("tx0").getDouble(0.00);
140 | }
141 |
142 | /**
143 | * @return the vertical offset from crosshair to target (-20.5 degrees to 20.5 degrees)
144 | */
145 | public double getVerticalOffsetFromTargetInDegrees() {
146 | return getEntry("ty").getDouble(0.00);
147 | }
148 |
149 | /**
150 | * @return the raw vertical offset from crosshair to target in pixels (-1 to 1)
151 | */
152 | public double getVerticalOffsetFromTargetInPixels() {
153 | return getEntry("ty0").getDouble(0.00);
154 | }
155 |
156 | /**
157 | * @return the area that the detected target takes up in total camera FOV (0% to 100%)
158 | */
159 | public double getTargetAreaPercentage() {
160 | return getEntry("ta").getDouble(0.00);
161 | }
162 |
163 | /**
164 | * @return the target skew or rotation (-90 degrees to 0 degrees)
165 | */
166 | public double getTargetSkew() {
167 | return getEntry("ts").getDouble(0.00);
168 | }
169 |
170 | /**
171 | * @return target latency (ms)
172 | */
173 | public double getTargetLatency() {
174 | return getEntry("tl").getDouble(0.00);
175 | }
176 |
177 | /**
178 | * @return the target width in pixels, depending on the camera resolution
179 | */
180 | public double getTargetWidthInPixels() {
181 | return getEntry("thor").getDouble(0.00);
182 | }
183 |
184 | /**
185 | * @return the target height in pixels, depending on the camera resolution
186 | */
187 | public double getTargetHeightInPixels() {
188 | return getEntry("tvert").getDouble(0.00);
189 | }
190 |
191 | /**
192 | * Sets the camera's mode to either vision processor or driver camera.
193 | *
194 | * @param mode the {@link CamMode}
195 | */
196 | public void setCamMode(CamMode mode) {
197 | int modeNum = mode.getCamMode();
198 | getEntry("camMode").setNumber(modeNum);
199 | }
200 |
201 | /**
202 | * Sets the LED's mode.
203 | *
204 | * @param mode the {@link LedMode}
205 | */
206 | public void setLedMode(LedMode mode) {
207 | int modeNum = mode.getLedMode();
208 | getEntry("ledMode").setNumber(modeNum);
209 | }
210 | }
211 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/MotorControllerGroup.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.util.sendable.Sendable;
4 | import edu.wpi.first.util.sendable.SendableBuilder;
5 | import edu.wpi.first.util.sendable.SendableRegistry;
6 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
7 |
8 | import java.util.List;
9 |
10 | public class MotorControllerGroup implements MotorController, Sendable, AutoCloseable {
11 |
12 | private final List extends MotorController> motorControllers;
13 | private boolean inverted;
14 |
15 | public MotorControllerGroup(MotorController... motorControllers) {
16 | this.motorControllers = List.of(motorControllers);
17 | }
18 |
19 | @Override
20 | public void close() {
21 | SendableRegistry.remove(this);
22 | }
23 |
24 | @Override
25 | public void set(double speed) {
26 | motorControllers.forEach(m -> m.set(inverted ? -speed : speed));
27 | }
28 |
29 | @Override
30 | public void setVoltage(double outputVolts) {
31 | motorControllers.forEach(m -> m.setVoltage(inverted ? -outputVolts : outputVolts));
32 | }
33 |
34 | @Override
35 | public double get() {
36 | return motorControllers.get(0).get();
37 | }
38 |
39 | @Override
40 | public void disable() {
41 | motorControllers.forEach(MotorController::disable);
42 | }
43 |
44 | @Override
45 | public void stopMotor() {
46 | motorControllers.forEach(MotorController::stopMotor);
47 | }
48 |
49 | @Override
50 | public void initSendable(SendableBuilder builder) {
51 | builder.setSmartDashboardType("Motor Controller");
52 | builder.setActuator(true);
53 | builder.setSafeState(this::stopMotor);
54 | builder.addDoubleProperty("Value", this::get, this::set);
55 | }
56 |
57 | @Override
58 | public boolean getInverted() {
59 | return inverted;
60 | }
61 |
62 | @Override
63 | public void setInverted(boolean isInverted) {
64 | inverted = isInverted;
65 | }
66 | }
67 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/PigeonWrapper.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import com.ctre.phoenix.motorcontrol.can.TalonSRX;
4 | import com.ctre.phoenix.sensors.PigeonIMU;
5 |
6 | /**
7 | * A wrapper class for the pigeon IMU sensor.
8 | *
9 | * @author Tal Sitton
10 | */
11 | public class PigeonWrapper {
12 |
13 | public double[] values = new double[3];
14 | protected final PigeonIMU pigeon;
15 |
16 | public PigeonWrapper(int canPort) {
17 | pigeon = new PigeonIMU(canPort);
18 | }
19 |
20 | public PigeonWrapper(TalonSRX talonSRX) {
21 | pigeon = new PigeonIMU(talonSRX);
22 | }
23 |
24 | /**
25 | * Resets the yaw.
26 | */
27 | public void reset() {
28 | setYaw(0);
29 | }
30 |
31 | /**
32 | * Calibrates the pigeon based on the yaw sent.
33 | *
34 | * @param yaw the yaw the pigeon shall be calibrated to
35 | */
36 | public void calibrate(double yaw) {
37 | pigeon.enterCalibrationMode(PigeonIMU.CalibrationMode.BootTareGyroAccel);
38 | setYaw(yaw);
39 | }
40 |
41 | /**
42 | * Calibrates the pigeon wrapper to yaw 0.
43 | */
44 | public void calibrate() {
45 | calibrate(0);
46 | }
47 |
48 | /**
49 | * @return the X axis from the gyro
50 | */
51 | public double getX() {
52 | pigeon.getAccumGyro(values);
53 | return values[0];
54 | }
55 |
56 | /**
57 | * @return the Y axis from the gyro
58 | */
59 | public double getY() {
60 | pigeon.getAccumGyro(values);
61 | return values[1];
62 | }
63 |
64 | /**
65 | * @return the Z axis from the gyro
66 | */
67 | public double getZ() {
68 | pigeon.getAccumGyro(values);
69 | return values[2];
70 | }
71 |
72 | /**
73 | * If you don't know what yaw is, see here.
74 | *
75 | * @return the yaw
76 | */
77 | public double getYaw() {
78 | pigeon.getYawPitchRoll(values);
79 | return values[0];
80 | }
81 |
82 | /**
83 | * @param yaw If you don't know what yaw is, see here.
84 | */
85 | public void setYaw(double yaw) {
86 | pigeon.setYaw(yaw);
87 | }
88 | }
89 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/PlaystationControllerWrapper.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.wpilibj.DriverStation;
4 | import edu.wpi.first.wpilibj.Joystick;
5 | import edu.wpi.first.wpilibj.PS4Controller;
6 | import edu.wpi.first.wpilibj2.command.button.JoystickButton;
7 | import edu.wpi.first.wpilibj2.command.button.Trigger;
8 |
9 | /**
10 | * A class that handles the communication between a PS4 controller and the code.
11 | *
12 | * @author Ofri Rosenbaum
13 | */
14 | public class PlaystationControllerWrapper extends Joystick {
15 |
16 | protected final PS4Controller ps;
17 |
18 | /**
19 | * Constructs a new {@link PS4Controller} using the port of the USB on the {@link DriverStation}.
20 | *
21 | * @param port the port on the {@link DriverStation} that the controller is plugged in
22 | */
23 | public PlaystationControllerWrapper(int port) {
24 | super(port);
25 | ps = new PS4Controller(port);
26 | }
27 |
28 | public JoystickButton getCrossButton() {
29 | return new JoystickButton(this, PS4Controller.Button.kCross.value);
30 | }
31 |
32 | public JoystickButton getSquareButton() {
33 | return new JoystickButton(this, PS4Controller.Button.kSquare.value);
34 | }
35 |
36 | public JoystickButton getCircleButton() {
37 | return new JoystickButton(this, PS4Controller.Button.kCircle.value);
38 | }
39 |
40 | public JoystickButton getTriangleButton() {
41 | return new JoystickButton(this, PS4Controller.Button.kTriangle.value);
42 | }
43 |
44 | public JoystickButton getOptionsButton() {
45 | return new JoystickButton(this, PS4Controller.Button.kOptions.value);
46 | }
47 |
48 | public JoystickButton getShareButton() {
49 | return new JoystickButton(this, PS4Controller.Button.kShare.value);
50 | }
51 |
52 | public double getR2Axis() {
53 | return ps.getR2Axis();
54 | }
55 |
56 | public double getL2Axis() {
57 | return ps.getL2Axis();
58 | }
59 |
60 | public Trigger getR2Button() {
61 | return new Trigger(ps::getR2Button);
62 | }
63 |
64 | public Trigger getL2Button() {
65 | return new Trigger(ps::getL2Button);
66 | }
67 |
68 | public JoystickButton getR1Button() {
69 | return new JoystickButton(this, PS4Controller.Button.kR1.value);
70 | }
71 |
72 | public JoystickButton getL1Button() {
73 | return new JoystickButton(this, PS4Controller.Button.kL1.value);
74 | }
75 |
76 | public JoystickButton getRightStickButton() {
77 | return new JoystickButton(this, PS4Controller.Button.kR3.value);
78 | }
79 |
80 | public JoystickButton getLeftStickButton() {
81 | return new JoystickButton(this, PS4Controller.Button.kL3.value);
82 | }
83 |
84 | public JoystickButton getPlaystationButton() {
85 | return new JoystickButton(this, PS4Controller.Button.kPS.value);
86 | }
87 |
88 | public JoystickButton getTouchpadButton() {
89 | return new JoystickButton(this, PS4Controller.Button.kTouchpad.value);
90 | }
91 |
92 | public double getRightX() {
93 | return ps.getRightX();
94 | }
95 |
96 | public double getRightY() {
97 | return ps.getRightY();
98 | }
99 |
100 | public double getLeftX() {
101 | return ps.getLeftX();
102 | }
103 |
104 | public double getLeftY() {
105 | return ps.getLeftY();
106 | }
107 |
108 | public Trigger getUpButton() {
109 | return new Trigger(() -> getPOV() == DPAD.UP.value);
110 | }
111 |
112 | public Trigger getDownButton() {
113 | return new Trigger(() -> getPOV() == DPAD.DOWN.value);
114 | }
115 |
116 | public Trigger getLeftButton() {
117 | return new Trigger(() -> getPOV() == DPAD.LEFT.value);
118 | }
119 |
120 | public Trigger getRightButton() {
121 | return new Trigger(() -> getPOV() == DPAD.RIGHT.value);
122 | }
123 | }
124 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/TalonEncoder.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import com.ctre.phoenix.motorcontrol.FeedbackDevice;
4 | import com.ctre.phoenix.motorcontrol.can.BaseTalon;
5 | import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
6 |
7 | /**
8 | * This class makes an encoder that is connected to a {@link WPI_TalonSRX} to a PIDSource.
9 | *
10 | * @author Tuval Rivkinind Barlev
11 | */
12 | public class TalonEncoder {
13 |
14 | protected final BaseTalon talon;
15 | private double distancePerPulse;
16 |
17 | /**
18 | * Constructs the PIDSource using the talon and the number of counts per
19 | * revolution of the motor.
20 | *
21 | * @param talon The talon the encoder is connected to.
22 | * @param distancePerPulse Counts per revolution of the motor. Can be used to change the
23 | * scale of the value of the encoder.
24 | */
25 | public TalonEncoder(BaseTalon talon, double distancePerPulse) {
26 | talon.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, 0, 30);
27 | talon.setSensorPhase(true);
28 | this.talon = talon;
29 | this.distancePerPulse = distancePerPulse;
30 | }
31 |
32 | /**
33 | * Constructs the PIDSource using the talon. The source will return the raw
34 | * value of the encoder.
35 | *
36 | * @param talon The talon the encoder is connected to.
37 | */
38 | public TalonEncoder(BaseTalon talon) {
39 | this(talon, 1);
40 | }
41 |
42 | /**
43 | * Resets the talon's relative position
44 | */
45 | public void reset() {
46 | talon.setSelectedSensorPosition(0);
47 | }
48 |
49 | public double getDistancePerPulse() {
50 | return distancePerPulse;
51 | }
52 |
53 | public void setDistancePerPulse(double distancePerPulse) {
54 | this.distancePerPulse = distancePerPulse;
55 | }
56 |
57 | public double getVelocity() {
58 | return talon.getSelectedSensorVelocity() * distancePerPulse;
59 | }
60 |
61 | public double getPosition() {
62 | return talon.getSelectedSensorPosition() * distancePerPulse;
63 | }
64 | }
65 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/UnifiedControlMode.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import com.ctre.phoenix6.hardware.TalonFX;
4 | import com.ctre.phoenix6.signals.ControlModeValue;
5 | import com.revrobotics.spark.SparkBase;
6 |
7 | /**
8 | * A wrapper for the REV motor controllers and the {@link TalonFX} control modes.
9 | *
10 | * @author Yoel Perman Brilliant
11 | * @see ControlModeValue
12 | * @see SparkBase.ControlType
13 | */
14 | public enum UnifiedControlMode {
15 |
16 | POSITION(ControlModeValue.PositionDutyCycle, SparkBase.ControlType.kPosition),
17 | VELOCITY(ControlModeValue.VelocityDutyCycle, SparkBase.ControlType.kVelocity),
18 | CURRENT(ControlModeValue.TorqueCurrentFOC, SparkBase.ControlType.kCurrent),
19 | PERCENT_OUTPUT(ControlModeValue.DutyCycleOut, SparkBase.ControlType.kDutyCycle),
20 | TRAPEZOID_PROFILE(ControlModeValue.MotionMagicDutyCycle, SparkBase.ControlType.kMAXMotionPositionControl),
21 | VOLTAGE(ControlModeValue.VoltageOut, SparkBase.ControlType.kVoltage);
22 |
23 | private final ControlModeValue talonFXControlMode;
24 | private final SparkBase.ControlType sparkControlType;
25 |
26 | UnifiedControlMode(ControlModeValue talonFXControlMode, SparkBase.ControlType sparkControlType) {
27 | this.talonFXControlMode = talonFXControlMode;
28 | this.sparkControlType = sparkControlType;
29 | }
30 |
31 | public ControlModeValue getTalonFXControlMode() {
32 | return talonFXControlMode;
33 | }
34 |
35 | public SparkBase.ControlType getSparkControlType() {
36 | return sparkControlType;
37 | }
38 | }
39 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/XboxControllerWrapper.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util;
2 |
3 | import edu.wpi.first.wpilibj.DriverStation;
4 | import edu.wpi.first.wpilibj.Joystick;
5 | import edu.wpi.first.wpilibj.XboxController;
6 | import edu.wpi.first.wpilibj2.command.Command;
7 | import edu.wpi.first.wpilibj2.command.InstantCommand;
8 | import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
9 | import edu.wpi.first.wpilibj2.command.WaitCommand;
10 | import edu.wpi.first.wpilibj2.command.button.JoystickButton;
11 | import edu.wpi.first.wpilibj2.command.button.Trigger;
12 |
13 | /**
14 | * A class that handles the communication between an Xbox 360 or Xbox One controller and the code.
15 | *
16 | * @author Tal Sitton
17 | */
18 | public class XboxControllerWrapper extends Joystick {
19 |
20 | protected final XboxController xbox;
21 |
22 | /**
23 | * Constructs a new {@link XboxControllerWrapper} using the port of the USB on the {@link DriverStation}.
24 | *
25 | * @param port the port on the {@link DriverStation} that the controller is plugged in
26 | */
27 | public XboxControllerWrapper(int port) {
28 | super(port);
29 | xbox = new XboxController(port);
30 | }
31 |
32 | public JoystickButton getAButton() {
33 | return new JoystickButton(this, XboxController.Button.kA.value);
34 | }
35 |
36 | public JoystickButton getXButton() {
37 | return new JoystickButton(this, XboxController.Button.kX.value);
38 | }
39 |
40 | public JoystickButton getBButton() {
41 | return new JoystickButton(this, XboxController.Button.kB.value);
42 | }
43 |
44 | public JoystickButton getYButton() {
45 | return new JoystickButton(this, XboxController.Button.kY.value);
46 | }
47 |
48 | public JoystickButton getButtonStart() {
49 | return new JoystickButton(this, XboxController.Button.kStart.value);
50 | }
51 |
52 | public JoystickButton getButtonBack() {
53 | return new JoystickButton(this, XboxController.Button.kBack.value);
54 | }
55 |
56 | public double getRTAxis() {
57 | return xbox.getRightTriggerAxis();
58 | }
59 |
60 | public double getLTAxis() {
61 | return xbox.getLeftTriggerAxis();
62 | }
63 |
64 | public Trigger getRTButton() {
65 | return new Trigger(() -> xbox.getRightTriggerAxis() == 1);
66 | }
67 |
68 | public Trigger getLTButton() {
69 | return new Trigger(() -> xbox.getLeftTriggerAxis() == 1);
70 | }
71 |
72 | public JoystickButton getRBButton() {
73 | return new JoystickButton(this, XboxController.Button.kRightBumper.value);
74 | }
75 |
76 | public JoystickButton getLBButton() {
77 | return new JoystickButton(this, XboxController.Button.kLeftBumper.value);
78 | }
79 |
80 | public JoystickButton getRightStickButton() {
81 | return new JoystickButton(this, XboxController.Button.kRightStick.value);
82 | }
83 |
84 | public JoystickButton getLeftStickButton() {
85 | return new JoystickButton(this, XboxController.Button.kLeftStick.value);
86 | }
87 |
88 | public double getRightX() {
89 | return xbox.getRightX();
90 | }
91 |
92 | public double getRightY() {
93 | return xbox.getRightY();
94 | }
95 |
96 | public double getLeftX() {
97 | return xbox.getLeftX();
98 | }
99 |
100 | public double getLeftY() {
101 | return xbox.getLeftY();
102 | }
103 |
104 | public Trigger getUpButton() {
105 | return new Trigger(() -> getPOV() == DPAD.UP.value);
106 | }
107 |
108 | public Trigger getDownButton() {
109 | return new Trigger(() -> getPOV() == DPAD.DOWN.value);
110 | }
111 |
112 | public Trigger getLeftButton() {
113 | return new Trigger(() -> getPOV() == DPAD.LEFT.value);
114 | }
115 |
116 | public Trigger getRightButton() {
117 | return new Trigger(() -> getPOV() == DPAD.RIGHT.value);
118 | }
119 |
120 | public Trigger getUpperRightButton() {
121 | return new Trigger(() -> getPOV() == DPAD.UPPER_RIGHT.value);
122 | }
123 |
124 | public Trigger getLowerRightButton() {
125 | return new Trigger(() -> getPOV() == DPAD.LOWER_RIGHT.value);
126 | }
127 |
128 | public Trigger getLowerLeftButton() {
129 | return new Trigger(() -> getPOV() == DPAD.LOWER_LEFT.value);
130 | }
131 |
132 | public Trigger getUpperLeftButton() {
133 | return new Trigger(() -> getPOV() == DPAD.UPPER_LEFT.value);
134 | }
135 |
136 | public void setRumble(double value) {
137 | xbox.setRumble(RumbleType.kLeftRumble, value);
138 | xbox.setRumble(RumbleType.kRightRumble, value);
139 | }
140 |
141 | public void timeRumble(double value, double time) {
142 | Command command = new SequentialCommandGroup(
143 | new InstantCommand(() -> {
144 | setRumble(value);
145 | }),
146 | new WaitCommand(time),
147 | new InstantCommand(() -> {
148 | setRumble(0);
149 | })
150 | );
151 | command.schedule();
152 | }
153 | }
154 |
--------------------------------------------------------------------------------
/src/main/java/com/spikes2212/util/smartmotorcontrollers/SmartMotorController.java:
--------------------------------------------------------------------------------
1 | package com.spikes2212.util.smartmotorcontrollers;
2 |
3 | import com.spikes2212.control.FeedForwardSettings;
4 | import com.spikes2212.control.PIDSettings;
5 | import com.spikes2212.control.TrapezoidProfileSettings;
6 | import com.spikes2212.util.UnifiedControlMode;
7 | import edu.wpi.first.wpilibj.motorcontrol.MotorController;
8 |
9 | /**
10 | * A {@link MotorController} that can run control loops.
11 | *
12 | * @author Camellia Lami
13 | */
14 | public interface SmartMotorController extends MotorController {
15 |
16 | /**
17 | * Configures the loop's PID constants.
18 | */
19 | void configurePID(PIDSettings pidSettings);
20 |
21 | /**
22 | * Configures the loop's feed forward gains.
23 | */
24 | void configureFF(FeedForwardSettings feedForwardSettings);
25 |
26 |
27 | /**
28 | * Configures the loop's trapezoid profile settings.
29 | */
30 | void configureTrapezoid(TrapezoidProfileSettings trapezoidProfileSettings);
31 |
32 |
33 | /**
34 | * Configures the loop's settings.
35 | */
36 | default void configureLoop(PIDSettings pidSettings, FeedForwardSettings feedForwardSettings,
37 | TrapezoidProfileSettings trapezoidProfileSettings) {
38 | configurePID(pidSettings);
39 | configureFF(feedForwardSettings);
40 | configureTrapezoid(trapezoidProfileSettings);
41 | }
42 |
43 | /**
44 | * Sets the encoder's position.
45 | */
46 | void setPosition(double position);
47 |
48 | /**
49 | * Resets the encoder's position to 0.
50 | */
51 | default void resetPosition() {
52 | setPosition(0);
53 | }
54 |
55 | /**
56 | * Updates any control loops running on the drivetrain's motor controllers.
57 | *
58 | * @param controlMode the loop's control mode
59 | * @param setpoint the loop's target
60 | * @param pidSettings the PID constants
61 | * @param feedForwardSettings the feed forward gains
62 | * @param trapezoidProfileSettings the trapezoid profile settings
63 | * @param updatePeriodically whether to update the loop's constants periodically
64 | */
65 | void pidSet(UnifiedControlMode controlMode, double setpoint, PIDSettings pidSettings,
66 | FeedForwardSettings feedForwardSettings, TrapezoidProfileSettings trapezoidProfileSettings,
67 | boolean updatePeriodically);
68 |
69 | /**
70 | * Updates any control loops running on the drivetrain's motor controllers.
71 | *
72 | * @param controlMode the loop's control mode
73 | * @param setpoint the loop's target
74 | * @param acceleration the desired acceleration
75 | * @param pidSettings the PID constants
76 | * @param feedForwardSettings the feed forward gains
77 | * @param updatePeriodically whether to update the loop's constants periodically
78 | */
79 | void pidSet(UnifiedControlMode controlMode, double setpoint, double acceleration, PIDSettings pidSettings,
80 | FeedForwardSettings feedForwardSettings, boolean updatePeriodically);
81 |
82 | /**
83 | * Updates any control loops running on the drivetrain's motor controllers.
84 | *
85 | * @param controlMode the loop's control mode
86 | * @param setpoint the loop's target
87 | * @param pidSettings the PID constants
88 | * @param feedForwardSettings the feed forward gains
89 | * @param updatePeriodically whether to update the loop's constants periodically
90 | */
91 | void pidSet(UnifiedControlMode controlMode, double setpoint, PIDSettings pidSettings,
92 | FeedForwardSettings feedForwardSettings, boolean updatePeriodically);
93 |
94 | /**
95 | * Checks whether the loops are currently on the target setpoints.
96 | *
97 | * @param controlMode the loop's control type
98 | * @param tolerance the maximum difference from the target to still consider the loop to be on target
99 | * @param setpoint the wanted setpoint
100 | * @return {@code true} when on target setpoint, {@code false} otherwise
101 | */
102 | boolean onTarget(UnifiedControlMode controlMode, double tolerance, double setpoint);
103 |
104 | double getPosition();
105 |
106 | double getVelocity();
107 | }
108 |
--------------------------------------------------------------------------------