)
-
-install(TARGETS wpilibOldCommands EXPORT wpilibOldCommands DESTINATION "${main_lib_dest}")
-install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibOldCommands")
-
-if (MSVC OR FLAT_INSTALL_WPILIB)
- set(wpilibOldCommands_config_dir ${wpilib_dest})
- else()
- set(wpilibOldCommands_config_dir share/wpilibOldCommands)
- endif()
-
- configure_file(wpilibOldCommands-config.cmake.in ${WPILIB_BINARY_DIR}/wpilibOldCommands-config.cmake)
- install(FILES ${WPILIB_BINARY_DIR}/wpilibOldCommands-config.cmake DESTINATION ${wpilibOldCommands_config_dir})
- install(EXPORT wpilibOldCommands DESTINATION ${wpilibOldCommands_config_dir})
-
- if (WITH_TESTS)
- wpilib_add_test(wpilibOldCommands src/test/native/cpp)
- target_include_directories(wpilibOldCommands_test PRIVATE src/test/native/include)
- target_link_libraries(wpilibOldCommands_test wpilibOldCommands gmock_main)
- endif()
diff --git a/wpilibOldCommands/WPILibOldCommands.json b/wpilibOldCommands/WPILibOldCommands.json
deleted file mode 100644
index d26cc4b863..0000000000
--- a/wpilibOldCommands/WPILibOldCommands.json
+++ /dev/null
@@ -1,37 +0,0 @@
-{
- "fileName": "WPILibOldCommands.json",
- "name": "WPILib-Old-Commands",
- "version": "1.0.0",
- "uuid": "b066afc2-5c18-43c4-b758-43381fcb275e",
- "mavenUrls": [],
- "jsonUrl": "",
- "javaDependencies": [
- {
- "groupId": "edu.wpi.first.wpilibOldCommands",
- "artifactId": "wpilibOldCommands-java",
- "version": "wpilib"
- }
- ],
- "jniDependencies": [],
- "cppDependencies": [
- {
- "groupId": "edu.wpi.first.wpilibOldCommands",
- "artifactId": "wpilibOldCommands-cpp",
- "version": "wpilib",
- "libName": "wpilibOldCommands",
- "headerClassifier": "headers",
- "sourcesClassifier": "sources",
- "sharedLibrary": true,
- "skipInvalidPlatforms": true,
- "binaryPlatforms": [
- "linuxathena",
- "linuxraspbian",
- "linuxaarch64bionic",
- "windowsx86-64",
- "windowsx86",
- "linuxx86-64",
- "osxx86-64"
- ]
- }
- ]
-}
diff --git a/wpilibOldCommands/build.gradle b/wpilibOldCommands/build.gradle
deleted file mode 100644
index 39870ee353..0000000000
--- a/wpilibOldCommands/build.gradle
+++ /dev/null
@@ -1,119 +0,0 @@
-ext {
- nativeName = 'wpilibOldCommands'
- devMain = 'edu.wpi.first.wpilibj.commands.DevMain'
-}
-
-evaluationDependsOn(':ntcore')
-evaluationDependsOn(':cscore')
-evaluationDependsOn(':hal')
-evaluationDependsOn(':wpimath')
-evaluationDependsOn(':wpilibc')
-evaluationDependsOn(':cameraserver')
-evaluationDependsOn(':wpilibj')
-
-apply from: "${rootDir}/shared/javacpp/setupBuild.gradle"
-
-dependencies {
- implementation project(':wpiutil')
- implementation project(':ntcore')
- implementation project(':cscore')
- implementation project(':hal')
- implementation project(':wpimath')
- implementation project(':wpilibj')
- devImplementation project(':wpiutil')
- devImplementation project(':ntcore')
- devImplementation project(':cscore')
- devImplementation project(':hal')
- devImplementation project(':wpimath')
- devImplementation project(':wpilibj')
-}
-
-nativeUtils.exportsConfigs {
- wpilibOldCommands {
- x86ExcludeSymbols = [
- '_CT??_R0?AV_System_error',
- '_CT??_R0?AVexception',
- '_CT??_R0?AVfailure',
- '_CT??_R0?AVruntime_error',
- '_CT??_R0?AVsystem_error',
- '_CTA5?AVfailure',
- '_TI5?AVfailure',
- '_CT??_R0?AVout_of_range',
- '_CTA3?AVout_of_range',
- '_TI3?AVout_of_range',
- '_CT??_R0?AVbad_cast'
- ]
- x64ExcludeSymbols = [
- '_CT??_R0?AV_System_error',
- '_CT??_R0?AVexception',
- '_CT??_R0?AVfailure',
- '_CT??_R0?AVruntime_error',
- '_CT??_R0?AVsystem_error',
- '_CTA5?AVfailure',
- '_TI5?AVfailure',
- '_CT??_R0?AVout_of_range',
- '_CTA3?AVout_of_range',
- '_TI3?AVout_of_range',
- '_CT??_R0?AVbad_cast'
- ]
- }
-}
-
-model {
- components {}
- binaries {
- all {
- if (!it.buildable || !(it instanceof NativeBinarySpec)) {
- return
- }
- lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
- lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
- project(':hal').addHalDependency(it, 'shared')
- lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
- lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
-
- if (it.component.name == "${nativeName}Dev") {
- lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
- project(':hal').addHalJniDependency(it)
- }
-
- if (it instanceof GoogleTestTestSuiteBinarySpec) {
- nativeUtils.useRequiredLibrary(it, 'opencv_shared')
- lib project: ':cscore', library: 'cscore', linkage: 'shared'
- }
- if ((it instanceof NativeExecutableBinarySpec || it instanceof GoogleTestTestSuiteBinarySpec) && it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
- nativeUtils.useRequiredLibrary(it, 'ni_link_libraries', 'ni_runtime_libraries')
- }
- }
- }
- tasks {
- def c = $.components
- def found = false
- def systemArch = getCurrentArch()
- c.each {
- if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
- it.binaries.each {
- if (!found) {
- def arch = it.targetPlatform.name
- if (arch == systemArch) {
- def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
-
- found = true
- }
- }
- }
- }
- }
- }
-}
-
-test {
- testLogging {
- outputs.upToDateWhen {false}
- showStandardStreams = true
- }
-}
-
-tasks.withType(JavaCompile) {
- options.compilerArgs += "-Xlint:-removal"
-}
diff --git a/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java b/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java
deleted file mode 100644
index 719fdccacb..0000000000
--- a/wpilibOldCommands/src/dev/java/edu/wpi/first/wpilibj/commands/DevMain.java
+++ /dev/null
@@ -1,21 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands;
-
-import edu.wpi.first.hal.HALUtil;
-import edu.wpi.first.networktables.NetworkTablesJNI;
-import edu.wpi.first.util.RuntimeDetector;
-
-public final class DevMain {
- /** Main entry point. */
- public static void main(String[] args) {
- System.out.println("Hello World!");
- System.out.println(RuntimeDetector.getPlatformPath());
- System.out.println(NetworkTablesJNI.now());
- System.out.println(HALUtil.getHALRuntimeType());
- }
-
- private DevMain() {}
-}
diff --git a/wpilibOldCommands/src/dev/native/cpp/main.cpp b/wpilibOldCommands/src/dev/native/cpp/main.cpp
deleted file mode 100644
index a3e363efca..0000000000
--- a/wpilibOldCommands/src/dev/native/cpp/main.cpp
+++ /dev/null
@@ -1,5 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-int main() {}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
deleted file mode 100644
index 03f93677ca..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
+++ /dev/null
@@ -1,817 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
-
-import edu.wpi.first.hal.FRCNetComm.tResourceType;
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.hal.util.BoundaryException;
-import edu.wpi.first.math.filter.LinearFilter;
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import java.util.concurrent.locks.ReentrantLock;
-
-/**
- * Class implements a PID Control Loop.
- *
- * Creates a separate thread which reads the given PIDSource and takes care of the integral
- * calculations, as well as writing the given PIDOutput.
- *
- *
This feedback controller runs in discrete time, so time deltas are not used in the integral
- * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
- * given set of PID constants.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable {
- public static final double kDefaultPeriod = 0.05;
- private static int instances;
-
- // Factor for "proportional" control
- @SuppressWarnings("MemberName")
- private double m_P;
-
- // Factor for "integral" control
- @SuppressWarnings("MemberName")
- private double m_I;
-
- // Factor for "derivative" control
- @SuppressWarnings("MemberName")
- private double m_D;
-
- // Factor for "feed forward" control
- @SuppressWarnings("MemberName")
- private double m_F;
-
- // |maximum output|
- private double m_maximumOutput = 1.0;
-
- // |minimum output|
- private double m_minimumOutput = -1.0;
-
- // Maximum input - limit setpoint to this
- private double m_maximumInput;
-
- // Minimum input - limit setpoint to this
- private double m_minimumInput;
-
- // Input range - difference between maximum and minimum
- private double m_inputRange;
-
- // Do the endpoints wrap around? (e.g., absolute encoder)
- private boolean m_continuous;
-
- // Is the PID controller enabled
- protected boolean m_enabled;
-
- // The prior error (used to compute velocity)
- private double m_prevError;
-
- // The sum of the errors for use in the integral calc
- private double m_totalError;
-
- // The tolerance object used to check if on target
- private Tolerance m_tolerance;
-
- private double m_setpoint;
- private double m_prevSetpoint;
-
- private double m_result;
-
- private LinearFilter m_filter;
-
- protected ReentrantLock m_thisMutex = new ReentrantLock();
-
- // Ensures when disable() is called, pidWrite() won't run if calculate()
- // is already running at that time.
- protected ReentrantLock m_pidWriteMutex = new ReentrantLock();
-
- protected PIDSource m_pidInput;
- protected PIDOutput m_pidOutput;
- protected Timer m_setpointTimer;
-
- /**
- * Tolerance is the type of tolerance used to specify if the PID controller is on target.
- *
- *
The various implementations of this class such as PercentageTolerance and AbsoluteTolerance
- * specify types of tolerance specifications to use.
- */
- public interface Tolerance {
- boolean onTarget();
- }
-
- /** Used internally for when Tolerance hasn't been set. */
- public static class NullTolerance implements Tolerance {
- @Override
- public boolean onTarget() {
- throw new IllegalStateException("No tolerance value set when calling onTarget().");
- }
- }
-
- public class PercentageTolerance implements Tolerance {
- private final double m_percentage;
-
- PercentageTolerance(double value) {
- m_percentage = value;
- }
-
- @Override
- public boolean onTarget() {
- return Math.abs(getError()) < m_percentage / 100 * m_inputRange;
- }
- }
-
- public class AbsoluteTolerance implements Tolerance {
- private final double m_value;
-
- AbsoluteTolerance(double value) {
- m_value = value;
- }
-
- @Override
- public boolean onTarget() {
- return Math.abs(getError()) < m_value;
- }
- }
-
- /**
- * Allocate a PID object with the given constants for P, I, D, and F.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param Kf the feed forward term
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output percentage
- */
- @SuppressWarnings("ParameterName")
- public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) {
- requireNonNullParam(source, "source", "PIDBase");
- requireNonNullParam(output, "output", "PIDBase");
-
- m_setpointTimer = new Timer();
- m_setpointTimer.start();
-
- m_P = Kp;
- m_I = Ki;
- m_D = Kd;
- m_F = Kf;
-
- m_pidInput = source;
- m_filter = LinearFilter.movingAverage(1);
-
- m_pidOutput = output;
-
- instances++;
- HAL.report(tResourceType.kResourceType_PIDController, instances);
- m_tolerance = new NullTolerance();
- SendableRegistry.add(this, "PIDController", instances);
- }
-
- /**
- * Allocate a PID object with the given constants for P, I, and D.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param source the PIDSource object that is used to get values
- * @param output the PIDOutput object that is set to the output percentage
- */
- @SuppressWarnings("ParameterName")
- public PIDBase(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
- this(Kp, Ki, Kd, 0.0, source, output);
- }
-
- @Override
- public void close() {
- SendableRegistry.remove(this);
- }
-
- /**
- * Read the input, calculate the output accordingly, and write to the output. This should only be
- * called by the PIDTask and is created during initialization.
- */
- @SuppressWarnings("LocalVariableName")
- protected void calculate() {
- if (m_pidInput == null || m_pidOutput == null) {
- return;
- }
-
- boolean enabled;
-
- m_thisMutex.lock();
- try {
- enabled = m_enabled;
- } finally {
- m_thisMutex.unlock();
- }
-
- if (enabled) {
- double input;
-
- // Storage for function inputs
- PIDSourceType pidSourceType;
- double P;
- double I;
- double D;
- double feedForward = calculateFeedForward();
- double minimumOutput;
- double maximumOutput;
-
- // Storage for function input-outputs
- double prevError;
- double error;
- double totalError;
-
- m_thisMutex.lock();
- try {
- input = m_filter.calculate(m_pidInput.pidGet());
-
- pidSourceType = m_pidInput.getPIDSourceType();
- P = m_P;
- I = m_I;
- D = m_D;
- minimumOutput = m_minimumOutput;
- maximumOutput = m_maximumOutput;
-
- prevError = m_prevError;
- error = getContinuousError(m_setpoint - input);
- totalError = m_totalError;
- } finally {
- m_thisMutex.unlock();
- }
-
- // Storage for function outputs
- double result;
-
- if (pidSourceType.equals(PIDSourceType.kRate)) {
- if (P != 0) {
- totalError = clamp(totalError + error, minimumOutput / P, maximumOutput / P);
- }
-
- result = P * totalError + D * error + feedForward;
- } else {
- if (I != 0) {
- totalError = clamp(totalError + error, minimumOutput / I, maximumOutput / I);
- }
-
- result = P * error + I * totalError + D * (error - prevError) + feedForward;
- }
-
- result = clamp(result, minimumOutput, maximumOutput);
-
- // Ensures m_enabled check and pidWrite() call occur atomically
- m_pidWriteMutex.lock();
- m_thisMutex.lock();
- try {
- if (m_enabled) {
- // Don't block other PIDController operations on pidWrite()
- m_thisMutex.unlock();
-
- m_pidOutput.pidWrite(result);
- }
- } finally {
- if (!m_enabled) {
- m_thisMutex.unlock();
- }
- m_pidWriteMutex.unlock();
- }
-
- m_thisMutex.lock();
- try {
- m_prevError = error;
- m_totalError = totalError;
- m_result = result;
- } finally {
- m_thisMutex.unlock();
- }
- }
- }
-
- /**
- * Calculate the feed forward term.
- *
- *
Both of the provided feed forward calculations are velocity feed forwards. If a different
- * feed forward calculation is desired, the user can override this function and provide his or her
- * own. This function does no synchronization because the PIDController class only calls it in
- * synchronized code, so be careful if calling it oneself.
- *
- *
If a velocity PID controller is being used, the F term should be set to 1 over the maximum
- * setpoint for the output. If a position PID controller is being used, the F term should be set
- * to 1 over the maximum speed for the output measured in setpoint units per this controller's
- * update period (see the default period in this class's constructor).
- *
- * @return The feedforward value.
- */
- protected double calculateFeedForward() {
- if (m_pidInput.getPIDSourceType().equals(PIDSourceType.kRate)) {
- return m_F * getSetpoint();
- } else {
- double temp = m_F * getDeltaSetpoint();
- m_prevSetpoint = m_setpoint;
- m_setpointTimer.reset();
- return temp;
- }
- }
-
- /**
- * Set the PID Controller gain parameters. Set the proportional, integral, and differential
- * coefficients.
- *
- * @param p Proportional coefficient
- * @param i Integral coefficient
- * @param d Differential coefficient
- */
- @Override
- @SuppressWarnings("ParameterName")
- public void setPID(double p, double i, double d) {
- m_thisMutex.lock();
- try {
- m_P = p;
- m_I = i;
- m_D = d;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the PID Controller gain parameters. Set the proportional, integral, and differential
- * coefficients.
- *
- * @param p Proportional coefficient
- * @param i Integral coefficient
- * @param d Differential coefficient
- * @param f Feed forward coefficient
- */
- @SuppressWarnings("ParameterName")
- public void setPID(double p, double i, double d, double f) {
- m_thisMutex.lock();
- try {
- m_P = p;
- m_I = i;
- m_D = d;
- m_F = f;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the Proportional coefficient of the PID controller gain.
- *
- * @param p Proportional coefficient
- */
- @SuppressWarnings("ParameterName")
- public void setP(double p) {
- m_thisMutex.lock();
- try {
- m_P = p;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the Integral coefficient of the PID controller gain.
- *
- * @param i Integral coefficient
- */
- @SuppressWarnings("ParameterName")
- public void setI(double i) {
- m_thisMutex.lock();
- try {
- m_I = i;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the Differential coefficient of the PID controller gain.
- *
- * @param d differential coefficient
- */
- @SuppressWarnings("ParameterName")
- public void setD(double d) {
- m_thisMutex.lock();
- try {
- m_D = d;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the Feed forward coefficient of the PID controller gain.
- *
- * @param f feed forward coefficient
- */
- @SuppressWarnings("ParameterName")
- public void setF(double f) {
- m_thisMutex.lock();
- try {
- m_F = f;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Get the Proportional coefficient.
- *
- * @return proportional coefficient
- */
- @Override
- public double getP() {
- m_thisMutex.lock();
- try {
- return m_P;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Get the Integral coefficient.
- *
- * @return integral coefficient
- */
- @Override
- public double getI() {
- m_thisMutex.lock();
- try {
- return m_I;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Get the Differential coefficient.
- *
- * @return differential coefficient
- */
- @Override
- public double getD() {
- m_thisMutex.lock();
- try {
- return m_D;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Get the Feed forward coefficient.
- *
- * @return feed forward coefficient
- */
- public double getF() {
- m_thisMutex.lock();
- try {
- return m_F;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Return the current PID result This is always centered on zero and constrained the the max and
- * min outs.
- *
- * @return the latest calculated output
- */
- public double get() {
- m_thisMutex.lock();
- try {
- return m_result;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the PID controller to consider the input to be continuous, Rather then using the max and
- * min input range as constraints, it considers them to be the same point and automatically
- * calculates the shortest route to the setpoint.
- *
- * @param continuous Set to true turns on continuous, false turns off continuous
- */
- public void setContinuous(boolean continuous) {
- if (continuous && m_inputRange <= 0) {
- throw new IllegalStateException("No input range set when calling setContinuous().");
- }
- m_thisMutex.lock();
- try {
- m_continuous = continuous;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the PID controller to consider the input to be continuous, Rather then using the max and
- * min input range as constraints, it considers them to be the same point and automatically
- * calculates the shortest route to the setpoint.
- */
- public void setContinuous() {
- setContinuous(true);
- }
-
- /**
- * Sets the maximum and minimum values expected from the input and setpoint.
- *
- * @param minimumInput the minimum value expected from the input
- * @param maximumInput the maximum value expected from the input
- */
- public void setInputRange(double minimumInput, double maximumInput) {
- m_thisMutex.lock();
- try {
- if (minimumInput > maximumInput) {
- throw new BoundaryException("Lower bound is greater than upper bound");
- }
- m_minimumInput = minimumInput;
- m_maximumInput = maximumInput;
- m_inputRange = maximumInput - minimumInput;
- } finally {
- m_thisMutex.unlock();
- }
-
- setSetpoint(m_setpoint);
- }
-
- /**
- * Sets the minimum and maximum values to write.
- *
- * @param minimumOutput the minimum percentage to write to the output
- * @param maximumOutput the maximum percentage to write to the output
- */
- public void setOutputRange(double minimumOutput, double maximumOutput) {
- m_thisMutex.lock();
- try {
- if (minimumOutput > maximumOutput) {
- throw new BoundaryException("Lower bound is greater than upper bound");
- }
- m_minimumOutput = minimumOutput;
- m_maximumOutput = maximumOutput;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the setpoint for the PIDController.
- *
- * @param setpoint the desired setpoint
- */
- @Override
- public void setSetpoint(double setpoint) {
- m_thisMutex.lock();
- try {
- if (m_maximumInput > m_minimumInput) {
- if (setpoint > m_maximumInput) {
- m_setpoint = m_maximumInput;
- } else if (setpoint < m_minimumInput) {
- m_setpoint = m_minimumInput;
- } else {
- m_setpoint = setpoint;
- }
- } else {
- m_setpoint = setpoint;
- }
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Returns the current setpoint of the PIDController.
- *
- * @return the current setpoint
- */
- @Override
- public double getSetpoint() {
- m_thisMutex.lock();
- try {
- return m_setpoint;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Returns the change in setpoint over time of the PIDController.
- *
- * @return the change in setpoint over time
- */
- public double getDeltaSetpoint() {
- m_thisMutex.lock();
- try {
- return (m_setpoint - m_prevSetpoint) / m_setpointTimer.get();
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Returns the current difference of the input from the setpoint.
- *
- * @return the current error
- */
- @Override
- public double getError() {
- m_thisMutex.lock();
- try {
- return getContinuousError(getSetpoint() - m_filter.calculate(m_pidInput.pidGet()));
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Returns the current difference of the error over the past few iterations. You can specify the
- * number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is
- * used for the onTarget() function.
- *
- * @return the current average of the error
- * @deprecated Use getError(), which is now already filtered.
- */
- @Deprecated
- public double getAvgError() {
- m_thisMutex.lock();
- try {
- return getError();
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Sets what type of input the PID controller will use.
- *
- * @param pidSource the type of input
- */
- public void setPIDSourceType(PIDSourceType pidSource) {
- m_pidInput.setPIDSourceType(pidSource);
- }
-
- /**
- * Returns the type of input the PID controller is using.
- *
- * @return the PID controller input type
- */
- public PIDSourceType getPIDSourceType() {
- return m_pidInput.getPIDSourceType();
- }
-
- /**
- * Set the PID tolerance using a Tolerance object. Tolerance can be specified as a percentage of
- * the range or as an absolute value. The Tolerance object encapsulates those options in an
- * object. Use it by creating the type of tolerance that you want to use: setTolerance(new
- * PIDController.AbsoluteTolerance(0.1))
- *
- * @param tolerance A tolerance object of the right type, e.g. PercentTolerance or
- * AbsoluteTolerance
- * @deprecated Use setPercentTolerance() instead.
- */
- @Deprecated
- public void setTolerance(Tolerance tolerance) {
- m_tolerance = tolerance;
- }
-
- /**
- * Set the absolute error which is considered tolerable for use with OnTarget.
- *
- * @param absvalue absolute error which is tolerable in the units of the input object
- */
- public void setAbsoluteTolerance(double absvalue) {
- m_thisMutex.lock();
- try {
- m_tolerance = new AbsoluteTolerance(absvalue);
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 =
- * 15 percent)
- *
- * @param percentage percent error which is tolerable
- */
- public void setPercentTolerance(double percentage) {
- m_thisMutex.lock();
- try {
- m_tolerance = new PercentageTolerance(percentage);
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Set the number of previous error samples to average for tolerancing. When determining whether a
- * mechanism is on target, the user may want to use a rolling average of previous measurements
- * instead of a precise position or velocity. This is useful for noisy sensors which return a few
- * erroneous measurements when the mechanism is on target. However, the mechanism will not
- * register as on target for at least the specified bufLength cycles.
- *
- * @param bufLength Number of previous cycles to average.
- * @deprecated Use a LinearFilter as the input.
- */
- @Deprecated
- public void setToleranceBuffer(int bufLength) {
- m_thisMutex.lock();
- try {
- m_filter = LinearFilter.movingAverage(bufLength);
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Return true if the error is within the percentage of the total input range, determined by
- * setTolerance. This assumes that the maximum and minimum input were set using setInput.
- *
- * @return true if the error is less than the tolerance
- */
- public boolean onTarget() {
- m_thisMutex.lock();
- try {
- return m_tolerance.onTarget();
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /** Reset the previous error, the integral term, and disable the controller. */
- @Override
- public void reset() {
- m_thisMutex.lock();
- try {
- m_prevError = 0;
- m_totalError = 0;
- m_result = 0;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /**
- * Passes the output directly to setSetpoint().
- *
- *
PIDControllers can be nested by passing a PIDController as another PIDController's output.
- * In that case, the output of the parent controller becomes the input (i.e., the reference) of
- * the child.
- *
- *
It is the caller's responsibility to put the data into a valid form for setSetpoint().
- */
- @Override
- public void pidWrite(double output) {
- setSetpoint(output);
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- builder.setSmartDashboardType("PIDController");
- builder.setSafeState(this::reset);
- builder.addDoubleProperty("p", this::getP, this::setP);
- builder.addDoubleProperty("i", this::getI, this::setI);
- builder.addDoubleProperty("d", this::getD, this::setD);
- builder.addDoubleProperty("f", this::getF, this::setF);
- builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint);
- }
-
- /**
- * Wraps error around for continuous inputs. The original error is returned if continuous mode is
- * disabled. This is an unsynchronized function.
- *
- * @param error The current error of the PID controller.
- * @return Error for continuous inputs.
- */
- protected double getContinuousError(double error) {
- if (m_continuous && m_inputRange > 0) {
- error %= m_inputRange;
- if (Math.abs(error) > m_inputRange / 2) {
- if (error > 0) {
- return error - m_inputRange;
- } else {
- return error + m_inputRange;
- }
- }
- }
-
- return error;
- }
-
- private static double clamp(double value, double low, double high) {
- return Math.max(low, Math.min(value, high));
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java
deleted file mode 100644
index 98580ef049..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDController.java
+++ /dev/null
@@ -1,182 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import edu.wpi.first.util.sendable.SendableBuilder;
-
-/**
- * Class implements a PID Control Loop.
- *
- *
Creates a separate thread which reads the given PIDSource and takes care of the integral
- * calculations, as well as writing the given PIDOutput.
- *
- *
This feedback controller runs in discrete time, so time deltas are not used in the integral
- * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
- * given set of PID constants.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} instead.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public class PIDController extends PIDBase implements Controller {
- Notifier m_controlLoop = new Notifier(this::calculate);
-
- /**
- * Allocate a PID object with the given constants for P, I, D, and F.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param Kf the feed forward term
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output percentage
- * @param period the loop time for doing calculations in seconds. This particularly affects
- * calculations of the integral and differential terms. The default is 0.05 (50ms).
- */
- @SuppressWarnings("ParameterName")
- public PIDController(
- double Kp,
- double Ki,
- double Kd,
- double Kf,
- PIDSource source,
- PIDOutput output,
- double period) {
- super(Kp, Ki, Kd, Kf, source, output);
- m_controlLoop.startPeriodic(period);
- }
-
- /**
- * Allocate a PID object with the given constants for P, I, D and period.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param source the PIDSource object that is used to get values
- * @param output the PIDOutput object that is set to the output percentage
- * @param period the loop time for doing calculations in seconds. This particularly affects
- * calculations of the integral and differential terms. The default is 0.05 (50ms).
- */
- @SuppressWarnings("ParameterName")
- public PIDController(
- double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period) {
- this(Kp, Ki, Kd, 0.0, source, output, period);
- }
-
- /**
- * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output percentage
- */
- @SuppressWarnings("ParameterName")
- public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
- this(Kp, Ki, Kd, source, output, kDefaultPeriod);
- }
-
- /**
- * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
- *
- * @param Kp the proportional coefficient
- * @param Ki the integral coefficient
- * @param Kd the derivative coefficient
- * @param Kf the feed forward term
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output percentage
- */
- @SuppressWarnings("ParameterName")
- public PIDController(
- double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) {
- this(Kp, Ki, Kd, Kf, source, output, kDefaultPeriod);
- }
-
- @Override
- public void close() {
- m_controlLoop.close();
- m_thisMutex.lock();
- try {
- m_pidOutput = null;
- m_pidInput = null;
- m_controlLoop = null;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /** Begin running the PIDController. */
- @Override
- public void enable() {
- m_thisMutex.lock();
- try {
- m_enabled = true;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /** Stop running the PIDController, this sets the output to zero before stopping. */
- @Override
- public void disable() {
- // Ensures m_enabled check and pidWrite() call occur atomically
- m_pidWriteMutex.lock();
- try {
- m_thisMutex.lock();
- try {
- m_enabled = false;
- } finally {
- m_thisMutex.unlock();
- }
-
- m_pidOutput.pidWrite(0);
- } finally {
- m_pidWriteMutex.unlock();
- }
- }
-
- /**
- * Set the enabled state of the PIDController.
- *
- * @param enable True to enable the PIDController.
- */
- public void setEnabled(boolean enable) {
- if (enable) {
- enable();
- } else {
- disable();
- }
- }
-
- /**
- * Return true if PIDController is enabled.
- *
- * @return True if PIDController is enabled.
- */
- public boolean isEnabled() {
- m_thisMutex.lock();
- try {
- return m_enabled;
- } finally {
- m_thisMutex.unlock();
- }
- }
-
- /** Reset the previous error, the integral term, and disable the controller. */
- @Override
- public void reset() {
- disable();
-
- super.reset();
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- super.initSendable(builder);
- builder.addBooleanProperty("enabled", this::isEnabled, this::setEnabled);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
deleted file mode 100644
index 4e7fd90d91..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * Interface for PID Controller.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-@Deprecated(since = "2020", forRemoval = true)
-@SuppressWarnings("SummaryJavadoc")
-public interface PIDInterface {
- void setPID(double p, double i, double d);
-
- double getP();
-
- double getI();
-
- double getD();
-
- void setSetpoint(double setpoint);
-
- double getSetpoint();
-
- double getError();
-
- void reset();
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
deleted file mode 100644
index a330daf8c8..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * This interface allows PIDController to write it's results to its output.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use DoubleConsumer and new PIDController class.
- */
-@FunctionalInterface
-@Deprecated(since = "2020", forRemoval = true)
-public interface PIDOutput {
- /**
- * Set the output to the value calculated by PIDController.
- *
- * @param output the value calculated by PIDController
- */
- void pidWrite(double output);
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
deleted file mode 100644
index e582168110..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * This interface allows for PIDController to automatically read from this object.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use DoubleSupplier and new PIDController class.
- */
-@Deprecated(since = "2020", forRemoval = true)
-public interface PIDSource {
- /**
- * Set which parameter of the device you are using as a process control variable.
- *
- * @param pidSource An enum to select the parameter.
- */
- void setPIDSourceType(PIDSourceType pidSource);
-
- /**
- * Get which parameter of the device you are using as a process control variable.
- *
- * @return the currently selected PID source parameter
- */
- PIDSourceType getPIDSourceType();
-
- /**
- * Get the result to use in PIDController.
- *
- * @return the result to use in PIDController
- */
- double pidGet();
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
deleted file mode 100644
index 3f41eb1924..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-/**
- * A description for the type of output value to provide to a PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-@Deprecated(since = "2020", forRemoval = true)
-public enum PIDSourceType {
- kDisplacement,
- kRate
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
deleted file mode 100644
index 8347993551..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-/**
- * This class provides an easy way to link commands to OI inputs.
- *
- *
It is very easy to link a button to a command. For instance, you could link the trigger button
- * of a joystick to a "score" command.
- *
- *
This class represents a subclass of Trigger that is specifically aimed at buttons on an
- * operator interface as a common use case of the more generalized Trigger objects. This is a simple
- * wrapper around Trigger with the method names renamed to fit the Button object use.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public abstract class Button extends Trigger {
- /**
- * Starts the given command whenever the button is newly pressed.
- *
- * @param command the command to start
- */
- public void whenPressed(final Command command) {
- whenActive(command);
- }
-
- /**
- * Constantly starts the given command while the button is held.
- *
- *
{@link Command#start()} will be called repeatedly while the button is held, and will be
- * canceled when the button is released.
- *
- * @param command the command to start
- */
- public void whileHeld(final Command command) {
- whileActive(command);
- }
-
- /**
- * Starts the command when the button is released.
- *
- * @param command the command to start
- */
- public void whenReleased(final Command command) {
- whenInactive(command);
- }
-
- /**
- * Toggles the command whenever the button is pressed (on then off then on).
- *
- * @param command the command to start
- */
- public void toggleWhenPressed(final Command command) {
- toggleWhenActive(command);
- }
-
- /**
- * Cancel the command when the button is pressed.
- *
- * @param command the command to start
- */
- public void cancelWhenPressed(final Command command) {
- cancelWhenActive(command);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
deleted file mode 100644
index 37cf28d9e8..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-/**
- * This {@link Button} is intended to be used within a program. The programmer can manually set its
- * value. * Also includes a setting for whether or not it should invert its value.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class InternalButton extends Button {
- private boolean m_pressed;
- private boolean m_inverted;
-
- /** Creates an InternalButton that is not inverted. */
- public InternalButton() {
- this(false);
- }
-
- /**
- * Creates an InternalButton which is inverted depending on the input.
- *
- * @param inverted if false, then this button is pressed when set to true, otherwise it is pressed
- * when set to false.
- */
- public InternalButton(boolean inverted) {
- m_pressed = m_inverted = inverted;
- }
-
- public void setInverted(boolean inverted) {
- m_inverted = inverted;
- }
-
- public void setPressed(boolean pressed) {
- m_pressed = pressed;
- }
-
- @Override
- public boolean get() {
- return m_pressed ^ m_inverted;
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
deleted file mode 100644
index 241683aafd..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.GenericHID;
-
-/**
- * A {@link Button} that gets its state from a {@link GenericHID}.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class JoystickButton extends Button {
- private final GenericHID m_joystick;
- private final int m_buttonNumber;
-
- /**
- * Create a joystick button for triggering commands.
- *
- * @param joystick The GenericHID object that has the button (e.g. Joystick, KinectStick, etc)
- * @param buttonNumber The button number (see {@link GenericHID#getRawButton(int) }
- */
- public JoystickButton(GenericHID joystick, int buttonNumber) {
- m_joystick = joystick;
- m_buttonNumber = buttonNumber;
- }
-
- /**
- * Gets the value of the joystick button.
- *
- * @return The value of the joystick button
- */
- @Override
- public boolean get() {
- return m_joystick.getRawButton(m_buttonNumber);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
deleted file mode 100644
index dd538bf5f5..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
+++ /dev/null
@@ -1,31 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.networktables.NetworkTable;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.networktables.NetworkTableInstance;
-
-/**
- * A {@link Button} that uses a {@link NetworkTable} boolean field.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class NetworkButton extends Button {
- private final NetworkTableEntry m_entry;
-
- public NetworkButton(String table, String field) {
- this(NetworkTableInstance.getDefault().getTable(table), field);
- }
-
- public NetworkButton(NetworkTable table, String field) {
- m_entry = table.getEntry(field);
- }
-
- @Override
- public boolean get() {
- return m_entry.getInstance().isConnected() && m_entry.getBoolean(false);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
deleted file mode 100644
index a58ba03eae..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.wpilibj.GenericHID;
-
-/**
- * A {@link Button} that gets its state from a POV on a {@link GenericHID}.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class POVButton extends Button {
- private final GenericHID m_joystick;
- private final int m_angle;
- private final int m_povNumber;
-
- /**
- * Creates a POV button for triggering commands.
- *
- * @param joystick The GenericHID object that has the POV
- * @param angle The desired angle in degrees (e.g. 90, 270)
- * @param povNumber The POV number (see {@link GenericHID#getPOV(int)})
- */
- public POVButton(GenericHID joystick, int angle, int povNumber) {
- m_joystick = joystick;
- m_angle = angle;
- m_povNumber = povNumber;
- }
-
- /**
- * Creates a POV button for triggering commands. By default, acts on POV 0
- *
- * @param joystick The GenericHID object that has the POV
- * @param angle The desired angle (e.g. 90, 270)
- */
- public POVButton(GenericHID joystick, int angle) {
- this(joystick, angle, 0);
- }
-
- /**
- * Checks whether the current value of the POV is the target angle.
- *
- * @return Whether the value of the POV matches the target angle
- */
- @Override
- public boolean get() {
- return m_joystick.getPOV(m_povNumber) == m_angle;
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
deleted file mode 100644
index 10240683f7..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
+++ /dev/null
@@ -1,183 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.buttons;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.command.Command;
-import edu.wpi.first.wpilibj.command.Scheduler;
-
-/**
- * This class provides an easy way to link commands to inputs.
- *
- *
It is very easy to link a button to a command. For instance, you could link the trigger button
- * of a joystick to a "score" command.
- *
- *
It is encouraged that teams write a subclass of Trigger if they want to have something unusual
- * (for instance, if they want to react to the user holding a button while the robot is reading a
- * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get
- * the full functionality of the Trigger class.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public abstract class Trigger implements Sendable {
- private volatile boolean m_sendablePressed;
-
- /**
- * Returns whether or not the trigger is active.
- *
- *
This method will be called repeatedly a command is linked to the Trigger.
- *
- * @return whether or not the trigger condition is active.
- */
- public abstract boolean get();
-
- /**
- * Returns whether get() return true or the internal table for SmartDashboard use is pressed.
- *
- * @return whether get() return true or the internal table for SmartDashboard use is pressed.
- */
- private boolean grab() {
- return get() || m_sendablePressed;
- }
-
- /**
- * Starts the given command whenever the trigger just becomes active.
- *
- * @param command the command to start
- */
- public void whenActive(final Command command) {
- new ButtonScheduler() {
- private boolean m_pressedLast = grab();
-
- @Override
- public void execute() {
- boolean pressed = grab();
-
- if (!m_pressedLast && pressed) {
- command.start();
- }
-
- m_pressedLast = pressed;
- }
- }.start();
- }
-
- /**
- * Constantly starts the given command while the button is held.
- *
- *
{@link Command#start()} will be called repeatedly while the trigger is active, and will be
- * canceled when the trigger becomes inactive.
- *
- * @param command the command to start
- */
- public void whileActive(final Command command) {
- new ButtonScheduler() {
- private boolean m_pressedLast = grab();
-
- @Override
- public void execute() {
- boolean pressed = grab();
-
- if (pressed) {
- command.start();
- } else if (m_pressedLast && !pressed) {
- command.cancel();
- }
-
- m_pressedLast = pressed;
- }
- }.start();
- }
-
- /**
- * Starts the command when the trigger becomes inactive.
- *
- * @param command the command to start
- */
- public void whenInactive(final Command command) {
- new ButtonScheduler() {
- private boolean m_pressedLast = grab();
-
- @Override
- public void execute() {
- boolean pressed = grab();
-
- if (m_pressedLast && !pressed) {
- command.start();
- }
-
- m_pressedLast = pressed;
- }
- }.start();
- }
-
- /**
- * Toggles a command when the trigger becomes active.
- *
- * @param command the command to toggle
- */
- public void toggleWhenActive(final Command command) {
- new ButtonScheduler() {
- private boolean m_pressedLast = grab();
-
- @Override
- public void execute() {
- boolean pressed = grab();
-
- if (!m_pressedLast && pressed) {
- if (command.isRunning()) {
- command.cancel();
- } else {
- command.start();
- }
- }
-
- m_pressedLast = pressed;
- }
- }.start();
- }
-
- /**
- * Cancels a command when the trigger becomes active.
- *
- * @param command the command to cancel
- */
- public void cancelWhenActive(final Command command) {
- new ButtonScheduler() {
- private boolean m_pressedLast = grab();
-
- @Override
- public void execute() {
- boolean pressed = grab();
-
- if (!m_pressedLast && pressed) {
- command.cancel();
- }
-
- m_pressedLast = pressed;
- }
- }.start();
- }
-
- /**
- * An internal class of {@link Trigger}. The user should ignore this, it is only public to
- * interface between packages.
- */
- public abstract static class ButtonScheduler {
- public abstract void execute();
-
- public void start() {
- Scheduler.getInstance().addButton(this);
- }
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- builder.setSmartDashboardType("Button");
- builder.setSafeState(() -> m_sendablePressed = false);
- builder.addBooleanProperty("pressed", this::grab, value -> m_sendablePressed = value);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java
deleted file mode 100644
index 8732186953..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Command.java
+++ /dev/null
@@ -1,627 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.RobotState;
-import edu.wpi.first.wpilibj.Timer;
-import java.util.Enumeration;
-
-/**
- * The Command class is at the very core of the entire command framework. Every command can be
- * started with a call to {@link Command#start() start()}. Once a command is started it will call
- * {@link Command#initialize() initialize()}, and then will repeatedly call {@link Command#execute()
- * execute()} until the {@link Command#isFinished() isFinished()} returns true. Once it does, {@link
- * Command#end() end()} will be called.
- *
- *
However, if at any point while it is running {@link Command#cancel() cancel()} is called, then
- * the command will be stopped and {@link Command#interrupted() interrupted()} will be called.
- *
- *
If a command uses a {@link Subsystem}, then it should specify that it does so by calling the
- * {@link Command#requires(Subsystem) requires(...)} method in its constructor. Note that a Command
- * may have multiple requirements, and {@link Command#requires(Subsystem) requires(...)} should be
- * called for each one.
- *
- *
If a command is running and a new command with shared requirements is started, then one of two
- * things will happen. If the active command is interruptible, then {@link Command#cancel()
- * cancel()} will be called and the command will be removed to make way for the new one. If the
- * active command is not interruptible, the other one will not even be started, and the active one
- * will continue functioning.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see Subsystem
- * @see CommandGroup
- * @see IllegalUseOfCommandException
- */
-public abstract class Command implements Sendable, AutoCloseable {
- /** The time since this command was initialized. */
- private double m_startTime = -1;
-
- /** The time (in seconds) before this command "times out" (or -1 if no timeout). */
- private double m_timeout = -1;
-
- /** Whether or not this command has been initialized. */
- private boolean m_initialized;
-
- /** The required subsystems. */
- private final Set m_requirements = new Set();
-
- /** Whether or not it is running. */
- private boolean m_running;
-
- /** Whether or not it is interruptible. */
- private boolean m_interruptible = true;
-
- /** Whether or not it has been canceled. */
- private boolean m_canceled;
-
- /** Whether or not it has been locked. */
- private boolean m_locked;
-
- /** Whether this command should run when the robot is disabled. */
- private boolean m_runWhenDisabled;
-
- /** Whether or not this command has completed running. */
- private boolean m_completed;
-
- /** The {@link CommandGroup} this is in. */
- private CommandGroup m_parent;
-
- /** Creates a new command. The name of this command will be set to its class name. */
- public Command() {
- String name = getClass().getName();
- SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1));
- }
-
- /**
- * Creates a new command with the given name.
- *
- * @param name the name for this command
- * @throws IllegalArgumentException if name is null
- */
- public Command(String name) {
- if (name == null) {
- throw new IllegalArgumentException("Name must not be null.");
- }
- SendableRegistry.add(this, name);
- }
-
- /**
- * Creates a new command with the given timeout and a default name. The default name is the name
- * of the class.
- *
- * @param timeout the time (in seconds) before this command "times out"
- * @throws IllegalArgumentException if given a negative timeout
- * @see Command#isTimedOut() isTimedOut()
- */
- public Command(double timeout) {
- this();
- if (timeout < 0) {
- throw new IllegalArgumentException("Timeout must not be negative. Given:" + timeout);
- }
- m_timeout = timeout;
- }
-
- /**
- * Creates a new command with the given timeout and a default name. The default name is the name
- * of the class.
- *
- * @param subsystem the subsystem that this command requires
- * @throws IllegalArgumentException if given a negative timeout
- * @see Command#isTimedOut() isTimedOut()
- */
- public Command(Subsystem subsystem) {
- this();
- requires(subsystem);
- }
-
- /**
- * Creates a new command with the given name.
- *
- * @param name the name for this command
- * @param subsystem the subsystem that this command requires
- * @throws IllegalArgumentException if name is null
- */
- public Command(String name, Subsystem subsystem) {
- this(name);
- requires(subsystem);
- }
-
- /**
- * Creates a new command with the given timeout and a default name. The default name is the name
- * of the class.
- *
- * @param timeout the time (in seconds) before this command "times out"
- * @param subsystem the subsystem that this command requires
- * @throws IllegalArgumentException if given a negative timeout
- * @see Command#isTimedOut() isTimedOut()
- */
- public Command(double timeout, Subsystem subsystem) {
- this(timeout);
- requires(subsystem);
- }
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time (in seconds) before this command "times out"
- * @throws IllegalArgumentException if given a negative timeout or name was null.
- * @see Command#isTimedOut() isTimedOut()
- */
- public Command(String name, double timeout) {
- this(name);
- if (timeout < 0) {
- throw new IllegalArgumentException("Timeout must not be negative. Given:" + timeout);
- }
- m_timeout = timeout;
- }
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time (in seconds) before this command "times out"
- * @param subsystem the subsystem that this command requires
- * @throws IllegalArgumentException if given a negative timeout
- * @throws IllegalArgumentException if given a negative timeout or name was null.
- * @see Command#isTimedOut() isTimedOut()
- */
- public Command(String name, double timeout, Subsystem subsystem) {
- this(name, timeout);
- requires(subsystem);
- }
-
- @Override
- public void close() {
- SendableRegistry.remove(this);
- }
-
- /**
- * Sets the timeout of this command.
- *
- * @param seconds the timeout (in seconds)
- * @throws IllegalArgumentException if seconds is negative
- * @see Command#isTimedOut() isTimedOut()
- */
- protected final synchronized void setTimeout(double seconds) {
- if (seconds < 0) {
- throw new IllegalArgumentException("Seconds must be positive. Given:" + seconds);
- }
- m_timeout = seconds;
- }
-
- /**
- * Returns the time since this command was initialized (in seconds). This function will work even
- * if there is no specified timeout.
- *
- * @return the time since this command was initialized (in seconds).
- */
- public final synchronized double timeSinceInitialized() {
- return m_startTime < 0 ? 0 : Timer.getFPGATimestamp() - m_startTime;
- }
-
- /**
- * This method specifies that the given {@link Subsystem} is used by this command. This method is
- * crucial to the functioning of the Command System in general.
- *
- *
Note that the recommended way to call this method is in the constructor.
- *
- * @param subsystem the {@link Subsystem} required
- * @throws IllegalArgumentException if subsystem is null
- * @throws IllegalUseOfCommandException if this command has started before or if it has been given
- * to a {@link CommandGroup}
- * @see Subsystem
- */
- protected synchronized void requires(Subsystem subsystem) {
- validate("Can not add new requirement to command");
- if (subsystem != null) {
- m_requirements.add(subsystem);
- } else {
- throw new IllegalArgumentException("Subsystem must not be null.");
- }
- }
-
- /**
- * Called when the command has been removed. This will call {@link Command#interrupted()
- * interrupted()} or {@link Command#end() end()}.
- */
- synchronized void removed() {
- if (m_initialized) {
- if (isCanceled()) {
- interrupted();
- _interrupted();
- } else {
- end();
- _end();
- }
- }
- m_initialized = false;
- m_canceled = false;
- m_running = false;
- m_completed = true;
- }
-
- /**
- * The run method is used internally to actually run the commands.
- *
- * @return whether or not the command should stay within the {@link Scheduler}.
- */
- synchronized boolean run() {
- if (!m_runWhenDisabled && m_parent == null && RobotState.isDisabled()) {
- cancel();
- }
- if (isCanceled()) {
- return false;
- }
- if (!m_initialized) {
- m_initialized = true;
- startTiming();
- _initialize();
- initialize();
- }
- _execute();
- execute();
- return !isFinished();
- }
-
- /** The initialize method is called the first time this Command is run after being started. */
- protected void initialize() {}
-
- /** A shadow method called before {@link Command#initialize() initialize()}. */
- @SuppressWarnings("MethodName")
- void _initialize() {}
-
- /** The execute method is called repeatedly until this Command either finishes or is canceled. */
- @SuppressWarnings("MethodName")
- protected void execute() {}
-
- /** A shadow method called before {@link Command#execute() execute()}. */
- @SuppressWarnings("MethodName")
- void _execute() {}
-
- /**
- * Returns whether this command is finished. If it is, then the command will be removed and {@link
- * Command#end() end()} will be called.
- *
- *
It may be useful for a team to reference the {@link Command#isTimedOut() isTimedOut()}
- * method for time-sensitive commands.
- *
- *
Returning false will result in the command never ending automatically. It may still be
- * canceled manually or interrupted by another command. Returning true will result in the command
- * executing once and finishing immediately. We recommend using {@link InstantCommand} for this.
- *
- * @return whether this command is finished.
- * @see Command#isTimedOut() isTimedOut()
- */
- protected abstract boolean isFinished();
-
- /**
- * Called when the command ended peacefully. This is where you may want to wrap up loose ends,
- * like shutting off a motor that was being used in the command.
- */
- protected void end() {}
-
- /** A shadow method called after {@link Command#end() end()}. */
- @SuppressWarnings("MethodName")
- void _end() {}
-
- /**
- * Called when the command ends because somebody called {@link Command#cancel() cancel()} or
- * another command shared the same requirements as this one, and booted it out.
- *
- *
This is where you may want to wrap up loose ends, like shutting off a motor that was being
- * used in the command.
- *
- *
Generally, it is useful to simply call the {@link Command#end() end()} method within this
- * method, as done here.
- */
- protected void interrupted() {
- end();
- }
-
- /** A shadow method called after {@link Command#interrupted() interrupted()}. */
- @SuppressWarnings("MethodName")
- void _interrupted() {}
-
- /**
- * Called to indicate that the timer should start. This is called right before {@link
- * Command#initialize() initialize()} is, inside the {@link Command#run() run()} method.
- */
- private void startTiming() {
- m_startTime = Timer.getFPGATimestamp();
- }
-
- /**
- * Returns whether or not the {@link Command#timeSinceInitialized() timeSinceInitialized()} method
- * returns a number which is greater than or equal to the timeout for the command. If there is no
- * timeout, this will always return false.
- *
- * @return whether the time has expired
- */
- protected synchronized boolean isTimedOut() {
- return m_timeout != -1 && timeSinceInitialized() >= m_timeout;
- }
-
- /**
- * Returns the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
- * Subsystems}) of this command.
- *
- * @return the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
- * Subsystems}) of this command
- */
- synchronized Enumeration> getRequirements() {
- return m_requirements.getElements();
- }
-
- /** Prevents further changes from being made. */
- synchronized void lockChanges() {
- m_locked = true;
- }
-
- /**
- * If changes are locked, then this will throw an {@link IllegalUseOfCommandException}.
- *
- * @param message the message to say (it is appended by a default message)
- */
- synchronized void validate(String message) {
- if (m_locked) {
- throw new IllegalUseOfCommandException(
- message + " after being started or being added to a command group");
- }
- }
-
- /**
- * Sets the parent of this command. No actual change is made to the group.
- *
- * @param parent the parent
- * @throws IllegalUseOfCommandException if this {@link Command} already is already in a group
- */
- synchronized void setParent(CommandGroup parent) {
- if (m_parent != null) {
- throw new IllegalUseOfCommandException(
- "Can not give command to a command group after already being put in a command group");
- }
- lockChanges();
- m_parent = parent;
- }
-
- /**
- * Returns whether the command has a parent.
- *
- * @return true if the command has a parent.
- */
- synchronized boolean isParented() {
- return m_parent != null;
- }
-
- /**
- * Clears list of subsystem requirements. This is only used by {@link ConditionalCommand} so
- * canceling the chosen command works properly in {@link CommandGroup}.
- */
- protected void clearRequirements() {
- m_requirements.clear();
- }
-
- /**
- * Starts up the command. Gets the command ready to start.
- *
- *
Note that the command will eventually start, however it will not necessarily do so
- * immediately, and may in fact be canceled before initialize is even called.
- *
- * @throws IllegalUseOfCommandException if the command is a part of a CommandGroup
- */
- public synchronized void start() {
- lockChanges();
- if (m_parent != null) {
- throw new IllegalUseOfCommandException(
- "Can not start a command that is a part of a command group");
- }
- Scheduler.getInstance().add(this);
- m_completed = false;
- }
-
- /**
- * This is used internally to mark that the command has been started. The lifecycle of a command
- * is:
- *
- *
startRunning() is called. run() is called (multiple times potentially) removed() is called.
- *
- *
It is very important that startRunning and removed be called in order or some assumptions of
- * the code will be broken.
- */
- synchronized void startRunning() {
- m_running = true;
- m_startTime = -1;
- }
-
- /**
- * Returns whether or not the command is running. This may return true even if the command has
- * just been canceled, as it may not have yet called {@link Command#interrupted()}.
- *
- * @return whether or not the command is running
- */
- public synchronized boolean isRunning() {
- return m_running;
- }
-
- /**
- * This will cancel the current command.
- *
- *
This will cancel the current command eventually. It can be called multiple times. And it can
- * be called when the command is not running. If the command is running though, then the command
- * will be marked as canceled and eventually removed.
- *
- *
A command can not be canceled if it is a part of a command group, you must cancel the
- * command group instead.
- *
- * @throws IllegalUseOfCommandException if this command is a part of a command group
- */
- public synchronized void cancel() {
- if (m_parent != null) {
- throw new IllegalUseOfCommandException(
- "Can not manually cancel a command in a command " + "group");
- }
- _cancel();
- }
-
- /**
- * This works like cancel(), except that it doesn't throw an exception if it is a part of a
- * command group. Should only be called by the parent command group.
- */
- @SuppressWarnings("MethodName")
- synchronized void _cancel() {
- if (isRunning()) {
- m_canceled = true;
- }
- }
-
- /**
- * Returns whether or not this has been canceled.
- *
- * @return whether or not this has been canceled
- */
- public synchronized boolean isCanceled() {
- return m_canceled;
- }
-
- /**
- * Whether or not this command has completed running.
- *
- * @return whether or not this command has completed running.
- */
- public synchronized boolean isCompleted() {
- return m_completed;
- }
-
- /**
- * Returns whether or not this command can be interrupted.
- *
- * @return whether or not this command can be interrupted
- */
- public synchronized boolean isInterruptible() {
- return m_interruptible;
- }
-
- /**
- * Sets whether or not this command can be interrupted.
- *
- * @param interruptible whether or not this command can be interrupted
- */
- protected synchronized void setInterruptible(boolean interruptible) {
- m_interruptible = interruptible;
- }
-
- /**
- * Checks if the command requires the given {@link Subsystem}.
- *
- * @param system the system
- * @return whether or not the subsystem is required, or false if given null
- */
- public synchronized boolean doesRequire(Subsystem system) {
- return m_requirements.contains(system);
- }
-
- /**
- * Returns the {@link CommandGroup} that this command is a part of. Will return null if this
- * {@link Command} is not in a group.
- *
- * @return the {@link CommandGroup} that this command is a part of (or null if not in group)
- */
- public synchronized CommandGroup getGroup() {
- return m_parent;
- }
-
- /**
- * Sets whether or not this {@link Command} should run when the robot is disabled.
- *
- *
By default a command will not run when the robot is disabled, and will in fact be canceled.
- *
- * @param run whether or not this command should run when the robot is disabled
- */
- public void setRunWhenDisabled(boolean run) {
- m_runWhenDisabled = run;
- }
-
- /**
- * Returns whether or not this {@link Command} will run when the robot is disabled, or if it will
- * cancel itself.
- *
- * @return True if this command will run when the robot is disabled.
- */
- public boolean willRunWhenDisabled() {
- return m_runWhenDisabled;
- }
-
- /**
- * Gets the name of this Command.
- *
- * @return Name
- */
- public String getName() {
- return SendableRegistry.getName(this);
- }
-
- /**
- * Sets the name of this Command.
- *
- * @param name name
- */
- public void setName(String name) {
- SendableRegistry.setName(this, name);
- }
-
- /**
- * Gets the subsystem name of this Command.
- *
- * @return Subsystem name
- */
- public String getSubsystem() {
- return SendableRegistry.getSubsystem(this);
- }
-
- /**
- * Sets the subsystem name of this Command.
- *
- * @param subsystem subsystem name
- */
- public void setSubsystem(String subsystem) {
- SendableRegistry.setSubsystem(this, subsystem);
- }
-
- /**
- * The string representation for a {@link Command} is by default its name.
- *
- * @return the string representation of this object
- */
- @Override
- public String toString() {
- return getName();
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- builder.setSmartDashboardType("Command");
- builder.addStringProperty(".name", this::getName, null);
- builder.addBooleanProperty(
- "running",
- this::isRunning,
- value -> {
- if (value) {
- if (!isRunning()) {
- start();
- }
- } else {
- if (isRunning()) {
- cancel();
- }
- }
- });
- builder.addBooleanProperty(".isParented", this::isParented, null);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
deleted file mode 100644
index 10f5066f4d..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
+++ /dev/null
@@ -1,410 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static java.util.Objects.requireNonNull;
-
-import java.util.Enumeration;
-import java.util.Vector;
-
-/**
- * A {@link CommandGroup} is a list of commands which are executed in sequence.
- *
- *
Commands in a {@link CommandGroup} are added using the {@link
- * CommandGroup#addSequential(Command) addSequential(...)} method and are called sequentially.
- * {@link CommandGroup CommandGroups} are themselves {@link Command commands} and can be given to
- * other {@link CommandGroup CommandGroups}.
- *
- *
{@link CommandGroup CommandGroups} will carry all of the requirements of their {@link Command
- * subcommands}. Additional requirements can be specified by calling {@link
- * CommandGroup#requires(Subsystem) requires(...)} normally in the constructor.
- *
- *
CommandGroups can also execute commands in parallel, simply by adding them using {@link
- * CommandGroup#addParallel(Command) addParallel(...)}.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Subsystem
- * @see IllegalUseOfCommandException
- */
-public class CommandGroup extends Command {
- /** The commands in this group (stored in entries). */
- @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
- private final Vector m_commands = new Vector<>();
- /*
- * Intentionally package private
- */
- /** The active children in this group (stored in entries). */
- @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
- final Vector m_children = new Vector<>();
- /** The current command, -1 signifies that none have been run. */
- private int m_currentCommandIndex = -1;
-
- /**
- * Creates a new {@link CommandGroup CommandGroup}. The name of this command will be set to its
- * class name.
- */
- public CommandGroup() {}
-
- /**
- * Creates a new {@link CommandGroup CommandGroup} with the given name.
- *
- * @param name the name for this command group
- * @throws IllegalArgumentException if name is null
- */
- public CommandGroup(String name) {
- super(name);
- }
-
- /**
- * Adds a new {@link Command Command} to the group. The {@link Command Command} will be started
- * after all the previously added {@link Command Commands}.
- *
- * Note that any requirements the given {@link Command Command} has will be added to the group.
- * For this reason, a {@link Command Command's} requirements can not be changed after being added
- * to a group.
- *
- *
It is recommended that this method be called in the constructor.
- *
- * @param command The {@link Command Command} to be added
- * @throws IllegalUseOfCommandException if the group has been started before or been given to
- * another group
- * @throws IllegalArgumentException if command is null
- */
- public final synchronized void addSequential(Command command) {
- validate("Can not add new command to command group");
- if (command == null) {
- throw new IllegalArgumentException("Given null command");
- }
-
- command.setParent(this);
-
- m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE));
- for (Enumeration> e = command.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
-
- /**
- * Adds a new {@link Command Command} to the group with a given timeout. The {@link Command
- * Command} will be started after all the previously added commands.
- *
- *
Once the {@link Command Command} is started, it will be run until it finishes or the time
- * expires, whichever is sooner. Note that the given {@link Command Command} will have no
- * knowledge that it is on a timer.
- *
- *
Note that any requirements the given {@link Command Command} has will be added to the group.
- * For this reason, a {@link Command Command's} requirements can not be changed after being added
- * to a group.
- *
- *
It is recommended that this method be called in the constructor.
- *
- * @param command The {@link Command Command} to be added
- * @param timeout The timeout (in seconds)
- * @throws IllegalUseOfCommandException if the group has been started before or been given to
- * another group or if the {@link Command Command} has been started before or been given to
- * another group
- * @throws IllegalArgumentException if command is null or timeout is negative
- */
- public final synchronized void addSequential(Command command, double timeout) {
- validate("Can not add new command to command group");
- if (command == null) {
- throw new IllegalArgumentException("Given null command");
- }
- if (timeout < 0) {
- throw new IllegalArgumentException("Can not be given a negative timeout");
- }
-
- command.setParent(this);
-
- m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE, timeout));
- for (Enumeration> e = command.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
-
- /**
- * Adds a new child {@link Command} to the group. The {@link Command} will be started after all
- * the previously added {@link Command Commands}.
- *
- *
Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
- * same time as the subsequent {@link Command Commands}. The child will run until either it
- * finishes, a new child with conflicting requirements is started, or the main sequence runs a
- * {@link Command} with conflicting requirements. In the latter two cases, the child will be
- * canceled even if it says it can't be interrupted.
- *
- *
Note that any requirements the given {@link Command Command} has will be added to the group.
- * For this reason, a {@link Command Command's} requirements can not be changed after being added
- * to a group.
- *
- *
It is recommended that this method be called in the constructor.
- *
- * @param command The command to be added
- * @throws IllegalUseOfCommandException if the group has been started before or been given to
- * another command group
- * @throws IllegalArgumentException if command is null
- */
- public final synchronized void addParallel(Command command) {
- requireNonNull(command, "Provided command was null");
- validate("Can not add new command to command group");
-
- command.setParent(this);
-
- m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD));
- for (Enumeration> e = command.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
-
- /**
- * Adds a new child {@link Command} to the group with the given timeout. The {@link Command} will
- * be started after all the previously added {@link Command Commands}.
- *
- *
Once the {@link Command Command} is started, it will run until it finishes, is interrupted,
- * or the time expires, whichever is sooner. Note that the given {@link Command Command} will have
- * no knowledge that it is on a timer.
- *
- *
Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
- * same time as the subsequent {@link Command Commands}. The child will run until either it
- * finishes, the timeout expires, a new child with conflicting requirements is started, or the
- * main sequence runs a {@link Command} with conflicting requirements. In the latter two cases,
- * the child will be canceled even if it says it can't be interrupted.
- *
- *
Note that any requirements the given {@link Command Command} has will be added to the group.
- * For this reason, a {@link Command Command's} requirements can not be changed after being added
- * to a group.
- *
- *
It is recommended that this method be called in the constructor.
- *
- * @param command The command to be added
- * @param timeout The timeout (in seconds)
- * @throws IllegalUseOfCommandException if the group has been started before or been given to
- * another command group
- * @throws IllegalArgumentException if command is null
- */
- public final synchronized void addParallel(Command command, double timeout) {
- requireNonNull(command, "Provided command was null");
- if (timeout < 0) {
- throw new IllegalArgumentException("Can not be given a negative timeout");
- }
- validate("Can not add new command to command group");
-
- command.setParent(this);
-
- m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD, timeout));
- for (Enumeration> e = command.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _initialize() {
- m_currentCommandIndex = -1;
- }
-
- @Override
- @SuppressWarnings({"MethodName", "PMD.AvoidReassigningLoopVariables"})
- void _execute() {
- Entry entry = null;
- Command cmd = null;
- boolean firstRun = false;
- if (m_currentCommandIndex == -1) {
- firstRun = true;
- m_currentCommandIndex = 0;
- }
-
- while (m_currentCommandIndex < m_commands.size()) {
- if (cmd != null) {
- if (entry.isTimedOut()) {
- cmd._cancel();
- }
- if (cmd.run()) {
- break;
- } else {
- cmd.removed();
- m_currentCommandIndex++;
- firstRun = true;
- cmd = null;
- continue;
- }
- }
-
- entry = m_commands.elementAt(m_currentCommandIndex);
- cmd = null;
-
- switch (entry.m_state) {
- case Entry.IN_SEQUENCE:
- cmd = entry.m_command;
- if (firstRun) {
- cmd.startRunning();
- cancelConflicts(cmd);
- }
- firstRun = false;
- break;
- case Entry.BRANCH_PEER:
- m_currentCommandIndex++;
- entry.m_command.start();
- break;
- case Entry.BRANCH_CHILD:
- m_currentCommandIndex++;
- cancelConflicts(entry.m_command);
- entry.m_command.startRunning();
- m_children.addElement(entry);
- break;
- default:
- break;
- }
- }
-
- // Run Children
- for (int i = 0; i < m_children.size(); i++) {
- entry = m_children.elementAt(i);
- Command child = entry.m_command;
- if (entry.isTimedOut()) {
- child._cancel();
- }
- if (!child.run()) {
- child.removed();
- m_children.removeElementAt(i--);
- }
- }
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _end() {
- // Theoretically, we don't have to check this, but we do if teams override
- // the isFinished method
- if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
- Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
- cmd._cancel();
- cmd.removed();
- }
-
- Enumeration> children = m_children.elements();
- while (children.hasMoreElements()) {
- Command cmd = ((Entry) children.nextElement()).m_command;
- cmd._cancel();
- cmd.removed();
- }
- m_children.removeAllElements();
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _interrupted() {
- _end();
- }
-
- /**
- * Returns true if all the {@link Command Commands} in this group have been started and have
- * finished.
- *
- *
Teams may override this method, although they should probably reference super.isFinished()
- * if they do.
- *
- * @return whether this {@link CommandGroup} is finished
- */
- @Override
- protected boolean isFinished() {
- return m_currentCommandIndex >= m_commands.size() && m_children.isEmpty();
- }
-
- // Can be overwritten by teams
- @Override
- protected void initialize() {}
-
- // Can be overwritten by teams
- @Override
- protected void execute() {}
-
- // Can be overwritten by teams
- @Override
- protected void end() {}
-
- // Can be overwritten by teams
- @Override
- protected void interrupted() {}
-
- /**
- * Returns whether or not this group is interruptible. A command group will be uninterruptible if
- * {@link CommandGroup#setInterruptible(boolean) setInterruptible(false)} was called or if it is
- * currently running an uninterruptible command or child.
- *
- * @return whether or not this {@link CommandGroup} is interruptible.
- */
- @Override
- public synchronized boolean isInterruptible() {
- if (!super.isInterruptible()) {
- return false;
- }
-
- if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
- Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
- if (!cmd.isInterruptible()) {
- return false;
- }
- }
-
- for (int i = 0; i < m_children.size(); i++) {
- if (!m_children.elementAt(i).m_command.isInterruptible()) {
- return false;
- }
- }
-
- return true;
- }
-
- @SuppressWarnings("PMD.AvoidReassigningLoopVariables")
- private void cancelConflicts(Command command) {
- for (int i = 0; i < m_children.size(); i++) {
- Command child = m_children.elementAt(i).m_command;
-
- Enumeration> requirements = command.getRequirements();
-
- while (requirements.hasMoreElements()) {
- Object requirement = requirements.nextElement();
- if (child.doesRequire((Subsystem) requirement)) {
- child._cancel();
- child.removed();
- m_children.removeElementAt(i--);
- break;
- }
- }
- }
- }
-
- private static class Entry {
- private static final int IN_SEQUENCE = 0;
- private static final int BRANCH_PEER = 1;
- private static final int BRANCH_CHILD = 2;
- private final Command m_command;
- private final int m_state;
- private final double m_timeout;
-
- Entry(Command command, int state) {
- m_command = command;
- m_state = state;
- m_timeout = -1;
- }
-
- Entry(Command command, int state, double timeout) {
- m_command = command;
- m_state = state;
- m_timeout = timeout;
- }
-
- boolean isTimedOut() {
- if (m_timeout == -1) {
- return false;
- } else {
- double time = m_command.timeSinceInitialized();
- return time != 0 && time >= m_timeout;
- }
- }
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
deleted file mode 100644
index 79c043d735..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
+++ /dev/null
@@ -1,163 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.Enumeration;
-
-/**
- * A {@link ConditionalCommand} is a {@link Command} that starts one of two commands.
- *
- *
A {@link ConditionalCommand} uses m_condition to determine whether it should run m_onTrue or
- * m_onFalse.
- *
- *
A {@link ConditionalCommand} adds the proper {@link Command} to the {@link Scheduler} during
- * {@link ConditionalCommand#initialize()} and then {@link ConditionalCommand#isFinished()} will
- * return true once that {@link Command} has finished executing.
- *
- *
If no {@link Command} is specified for m_onFalse, the occurrence of that condition will be a
- * no-op.
- *
- *
A ConditionalCommand will require the superset of subsystems of the onTrue and onFalse
- * commands.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Scheduler
- */
-public abstract class ConditionalCommand extends Command {
- /** The Command to execute if {@link ConditionalCommand#condition()} returns true. */
- private Command m_onTrue;
-
- /** The Command to execute if {@link ConditionalCommand#condition()} returns false. */
- private Command m_onFalse;
-
- /** Stores command chosen by condition. */
- private Command m_chosenCommand;
-
- private void requireAll() {
- if (m_onTrue != null) {
- for (Enumeration> e = m_onTrue.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
-
- if (m_onFalse != null) {
- for (Enumeration> e = m_onFalse.getRequirements(); e.hasMoreElements(); ) {
- requires((Subsystem) e.nextElement());
- }
- }
- }
-
- /**
- * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
- *
- *
Users of this constructor should also override condition().
- *
- * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
- */
- public ConditionalCommand(Command onTrue) {
- this(onTrue, null);
- }
-
- /**
- * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
- *
- *
Users of this constructor should also override condition().
- *
- * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
- * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
- */
- public ConditionalCommand(Command onTrue, Command onFalse) {
- m_onTrue = onTrue;
- m_onFalse = onFalse;
-
- requireAll();
- }
-
- /**
- * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
- *
- *
Users of this constructor should also override condition().
- *
- * @param name the name for this command group
- * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
- */
- public ConditionalCommand(String name, Command onTrue) {
- this(name, onTrue, null);
- }
-
- /**
- * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
- *
- *
Users of this constructor should also override condition().
- *
- * @param name the name for this command group
- * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
- * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
- */
- public ConditionalCommand(String name, Command onTrue, Command onFalse) {
- super(name);
- m_onTrue = onTrue;
- m_onFalse = onFalse;
-
- requireAll();
- }
-
- /**
- * The Condition to test to determine which Command to run.
- *
- * @return true if m_onTrue should be run or false if m_onFalse should be run.
- */
- protected abstract boolean condition();
-
- /** Calls {@link ConditionalCommand#condition()} and runs the proper command. */
- @Override
- protected void _initialize() {
- if (condition()) {
- m_chosenCommand = m_onTrue;
- } else {
- m_chosenCommand = m_onFalse;
- }
-
- if (m_chosenCommand != null) {
- /*
- * This is a hack to make canceling the chosen command inside a
- * CommandGroup work properly
- */
- m_chosenCommand.clearRequirements();
-
- m_chosenCommand.start();
- }
- super._initialize();
- }
-
- @Override
- protected synchronized void _cancel() {
- if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
- m_chosenCommand.cancel();
- }
-
- super._cancel();
- }
-
- @Override
- protected boolean isFinished() {
- if (m_chosenCommand != null) {
- return m_chosenCommand.isCompleted();
- } else {
- return true;
- }
- }
-
- @Override
- protected void _interrupted() {
- if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
- m_chosenCommand.cancel();
- }
-
- super._interrupted();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
deleted file mode 100644
index 833b4fb765..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This exception will be thrown if a command is used illegally. There are several ways for this to
- * happen.
- *
- *
Basically, a command becomes "locked" after it is first started or added to a command group.
- *
- *
This exception should be thrown if (after a command has been locked) its requirements change,
- * it is put into multiple command groups, it is started from outside its command group, or it adds
- * a new child.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-@SuppressWarnings("serial")
-public class IllegalUseOfCommandException extends RuntimeException {
- /** Instantiates an {@link IllegalUseOfCommandException}. */
- public IllegalUseOfCommandException() {}
-
- /**
- * Instantiates an {@link IllegalUseOfCommandException} with the given message.
- *
- * @param message the message
- */
- public IllegalUseOfCommandException(String message) {
- super(message);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
deleted file mode 100644
index 42278f6087..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
+++ /dev/null
@@ -1,108 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This command will execute once, then finish immediately afterward.
- *
- *
Subclassing {@link InstantCommand} is shorthand for returning true from {@link Command
- * isFinished}.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class InstantCommand extends Command {
- private Runnable m_func;
-
- public InstantCommand() {}
-
- /**
- * Creates a new {@link InstantCommand InstantCommand} with the given name.
- *
- * @param name the name for this command
- */
- public InstantCommand(String name) {
- super(name);
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand} with the given requirement.
- *
- * @param subsystem the subsystem this command requires
- */
- public InstantCommand(Subsystem subsystem) {
- super(subsystem);
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand} with the given name and requirement.
- *
- * @param name the name for this command
- * @param subsystem the subsystem this command requires
- */
- public InstantCommand(String name, Subsystem subsystem) {
- super(name, subsystem);
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand}.
- *
- * @param func the function to run when {@link Command#initialize() initialize()} is run
- */
- public InstantCommand(Runnable func) {
- m_func = func;
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand}.
- *
- * @param name the name for this command
- * @param func the function to run when {@link Command#initialize() initialize()} is run
- */
- public InstantCommand(String name, Runnable func) {
- super(name);
- m_func = func;
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand}.
- *
- * @param requirement the subsystem this command requires
- * @param func the function to run when {@link Command#initialize() initialize()} is run
- */
- public InstantCommand(Subsystem requirement, Runnable func) {
- super(requirement);
- m_func = func;
- }
-
- /**
- * Creates a new {@link InstantCommand InstantCommand}.
- *
- * @param name the name for this command
- * @param requirement the subsystem this command requires
- * @param func the function to run when {@link Command#initialize() initialize()} is run
- */
- public InstantCommand(String name, Subsystem requirement, Runnable func) {
- super(name, requirement);
- m_func = func;
- }
-
- @Override
- protected boolean isFinished() {
- return true;
- }
-
- /**
- * Trigger the stored function.
- *
- *
Called just before this Command runs the first time.
- */
- @Override
- protected void _initialize() {
- super._initialize();
- if (m_func != null) {
- m_func.run();
- }
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
deleted file mode 100644
index b657ba7a9a..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * An element that is in a LinkedList.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-class LinkedListElement {
- private LinkedListElement m_next;
- private LinkedListElement m_previous;
- private Command m_data;
-
- public void setData(Command newData) {
- m_data = newData;
- }
-
- public Command getData() {
- return m_data;
- }
-
- public LinkedListElement getNext() {
- return m_next;
- }
-
- public LinkedListElement getPrevious() {
- return m_previous;
- }
-
- public void add(LinkedListElement listElement) {
- if (m_next == null) {
- m_next = listElement;
- m_next.m_previous = this;
- } else {
- m_next.m_previous = listElement;
- listElement.m_next = m_next;
- listElement.m_previous = this;
- m_next = listElement;
- }
- }
-
- @SuppressWarnings("PMD.EmptyIfStmt")
- public LinkedListElement remove() {
- if (m_previous == null && m_next == null) {
- // no-op
- } else if (m_next == null) {
- m_previous.m_next = null;
- } else if (m_previous == null) {
- m_next.m_previous = null;
- } else {
- m_next.m_previous = m_previous;
- m_previous.m_next = m_next;
- }
- LinkedListElement returnNext = m_next;
- m_next = null;
- m_previous = null;
- return returnNext;
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
deleted file mode 100644
index 1f63267db9..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
+++ /dev/null
@@ -1,268 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.PIDController;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * This class defines a {@link Command} which interacts heavily with a PID loop.
- *
- *
It provides some convenience methods to run an internal {@link PIDController} . It will also
- * start and stop said {@link PIDController} when the {@link PIDCommand} is first initialized and
- * ended/interrupted.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public abstract class PIDCommand extends Command {
- /** The internal {@link PIDController}. */
- private final PIDController m_controller;
- /** An output which calls {@link PIDCommand#usePIDOutput(double)}. */
- private final PIDOutput m_output = this::usePIDOutput;
- /** A source which calls {@link PIDCommand#returnPIDInput()}. */
- private final PIDSource m_source =
- new PIDSource() {
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {}
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return PIDSourceType.kDisplacement;
- }
-
- @Override
- public double pidGet() {
- return returnPIDInput();
- }
- };
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
- *
- * @param name the name of the command
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- public PIDCommand(String name, double p, double i, double d) {
- super(name);
- m_controller = new PIDController(p, i, d, m_source, m_output);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
- * the time between PID loop calculations to be equal to the given period.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param period the time (in seconds) between calculations
- */
- public PIDCommand(String name, double p, double i, double d, double period) {
- super(name);
- m_controller = new PIDController(p, i, d, m_source, m_output, period);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
- * class name as its name.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- public PIDCommand(double p, double i, double d) {
- m_controller = new PIDController(p, i, d, m_source, m_output);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
- * class name as its name. It will also space the time between PID loop calculations to be equal
- * to the given period.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param period the time (in seconds) between calculations
- */
- public PIDCommand(double p, double i, double d, double period) {
- m_controller = new PIDController(p, i, d, m_source, m_output, period);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
- *
- * @param name the name of the command
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param subsystem the subsystem that this command requires
- */
- public PIDCommand(String name, double p, double i, double d, Subsystem subsystem) {
- super(name, subsystem);
- m_controller = new PIDController(p, i, d, m_source, m_output);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
- * the time between PID loop calculations to be equal to the given period.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param period the time (in seconds) between calculations
- * @param subsystem the subsystem that this command requires
- */
- public PIDCommand(String name, double p, double i, double d, double period, Subsystem subsystem) {
- super(name, subsystem);
- m_controller = new PIDController(p, i, d, m_source, m_output, period);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
- * class name as its name.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param subsystem the subsystem that this command requires
- */
- public PIDCommand(double p, double i, double d, Subsystem subsystem) {
- super(subsystem);
- m_controller = new PIDController(p, i, d, m_source, m_output);
- }
-
- /**
- * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
- * class name as its name. It will also space the time between PID loop calculations to be equal
- * to the given period.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param period the time (in seconds) between calculations
- * @param subsystem the subsystem that this command requires
- */
- public PIDCommand(double p, double i, double d, double period, Subsystem subsystem) {
- super(subsystem);
- m_controller = new PIDController(p, i, d, m_source, m_output, period);
- }
-
- /**
- * Returns the {@link PIDController} used by this {@link PIDCommand}. Use this if you would like
- * to fine tune the pid loop.
- *
- * @return the {@link PIDController} used by this {@link PIDCommand}
- */
- protected PIDController getPIDController() {
- return m_controller;
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _initialize() {
- m_controller.enable();
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _end() {
- m_controller.disable();
- }
-
- @Override
- @SuppressWarnings("MethodName")
- void _interrupted() {
- _end();
- }
-
- /**
- * Adds the given value to the setpoint. If {@link PIDCommand#setInputRange(double, double)
- * setInputRange(...)} was used, then the bounds will still be honored by this method.
- *
- * @param deltaSetpoint the change in the setpoint
- */
- public void setSetpointRelative(double deltaSetpoint) {
- setSetpoint(getSetpoint() + deltaSetpoint);
- }
-
- /**
- * Sets the setpoint to the given value. If {@link PIDCommand#setInputRange(double, double)
- * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
- * range.
- *
- * @param setpoint the new setpoint
- */
- protected void setSetpoint(double setpoint) {
- m_controller.setSetpoint(setpoint);
- }
-
- /**
- * Returns the setpoint.
- *
- * @return the setpoint
- */
- protected double getSetpoint() {
- return m_controller.getSetpoint();
- }
-
- /**
- * Returns the current position.
- *
- * @return the current position
- */
- protected double getPosition() {
- return returnPIDInput();
- }
-
- /**
- * Sets the maximum and minimum values expected from the input and setpoint.
- *
- * @param minimumInput the minimum value expected from the input and setpoint
- * @param maximumInput the maximum value expected from the input and setpoint
- */
- protected void setInputRange(double minimumInput, double maximumInput) {
- m_controller.setInputRange(minimumInput, maximumInput);
- }
-
- /**
- * Returns the input for the pid loop.
- *
- *
It returns the input for the pid loop, so if this command was based off of a gyro, then it
- * should return the angle of the gyro.
- *
- *
All subclasses of {@link PIDCommand} must override this method.
- *
- *
This method will be called in a different thread then the {@link Scheduler} thread.
- *
- * @return the value the pid loop should use as input
- */
- protected abstract double returnPIDInput();
-
- /**
- * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
- * This method is a good time to set motor values, maybe something along the lines of
- * driveline.tankDrive(output, -output)
- *
- *
All subclasses of {@link PIDCommand} must override this method.
- *
- *
This method will be called in a different thread then the {@link Scheduler} thread.
- *
- * @param output the value the pid loop calculated
- */
- protected abstract void usePIDOutput(double output);
-
- @Override
- public void initSendable(SendableBuilder builder) {
- m_controller.initSendable(builder);
- super.initSendable(builder);
- builder.setSmartDashboardType("PIDCommand");
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
deleted file mode 100644
index 2fa18f1887..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
+++ /dev/null
@@ -1,266 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.PIDController;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * This class is designed to handle the case where there is a {@link Subsystem} which uses a single
- * {@link PIDController} almost constantly (for instance, an elevator which attempts to stay at a
- * constant height).
- *
- *
It provides some convenience methods to run an internal {@link PIDController} . It also allows
- * access to the internal {@link PIDController} in order to give total control to the programmer.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public abstract class PIDSubsystem extends Subsystem {
- /** The internal {@link PIDController}. */
- private final PIDController m_controller;
- /** An output which calls {@link PIDCommand#usePIDOutput(double)}. */
- private final PIDOutput m_output = this::usePIDOutput;
-
- /** A source which calls {@link PIDCommand#returnPIDInput()}. */
- private final PIDSource m_source =
- new PIDSource() {
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {}
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return PIDSourceType.kDisplacement;
- }
-
- @Override
- public double pidGet() {
- return returnPIDInput();
- }
- };
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- public PIDSubsystem(String name, double p, double i, double d) {
- super(name);
- m_controller = new PIDController(p, i, d, m_source, m_output);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feed forward value
- */
- public PIDSubsystem(String name, double p, double i, double d, double f) {
- super(name);
- m_controller = new PIDController(p, i, d, f, m_source, m_output);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values. It will also
- * space the time between PID loop calculations to be equal to the given period.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feed forward value
- * @param period the time (in seconds) between calculations
- */
- public PIDSubsystem(String name, double p, double i, double d, double f, double period) {
- super(name);
- m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
- * class name as its name.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- public PIDSubsystem(double p, double i, double d) {
- m_controller = new PIDController(p, i, d, m_source, m_output);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i, d, and f values. It will use
- * the class name as its name. It will also space the time between PID loop calculations to be
- * equal to the given period.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feed forward coefficient
- * @param period the time (in seconds) between calculations
- */
- public PIDSubsystem(double p, double i, double d, double f, double period) {
- m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
- * class name as its name. It will also space the time between PID loop calculations to be equal
- * to the given period.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param period the time (in seconds) between calculations
- */
- public PIDSubsystem(double p, double i, double d, double period) {
- m_controller = new PIDController(p, i, d, m_source, m_output, period);
- addChild("PIDController", m_controller);
- }
-
- /**
- * Returns the {@link PIDController} used by this {@link PIDSubsystem}. Use this if you would like
- * to fine tune the pid loop.
- *
- * @return the {@link PIDController} used by this {@link PIDSubsystem}
- */
- public PIDController getPIDController() {
- return m_controller;
- }
-
- /**
- * Adds the given value to the setpoint. If {@link PIDSubsystem#setInputRange(double, double)
- * setInputRange(...)} was used, then the bounds will still be honored by this method.
- *
- * @param deltaSetpoint the change in the setpoint
- */
- public void setSetpointRelative(double deltaSetpoint) {
- setSetpoint(getPosition() + deltaSetpoint);
- }
-
- /**
- * Sets the setpoint to the given value. If {@link PIDSubsystem#setInputRange(double, double)
- * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
- * range.
- *
- * @param setpoint the new setpoint
- */
- public void setSetpoint(double setpoint) {
- m_controller.setSetpoint(setpoint);
- }
-
- /**
- * Returns the setpoint.
- *
- * @return the setpoint
- */
- public double getSetpoint() {
- return m_controller.getSetpoint();
- }
-
- /**
- * Returns the current position.
- *
- * @return the current position
- */
- public double getPosition() {
- return returnPIDInput();
- }
-
- /**
- * Sets the maximum and minimum values expected from the input.
- *
- * @param minimumInput the minimum value expected from the input
- * @param maximumInput the maximum value expected from the output
- */
- public void setInputRange(double minimumInput, double maximumInput) {
- m_controller.setInputRange(minimumInput, maximumInput);
- }
-
- /**
- * Sets the maximum and minimum values to write.
- *
- * @param minimumOutput the minimum value to write to the output
- * @param maximumOutput the maximum value to write to the output
- */
- public void setOutputRange(double minimumOutput, double maximumOutput) {
- m_controller.setOutputRange(minimumOutput, maximumOutput);
- }
-
- /**
- * Set the absolute error which is considered tolerable for use with OnTarget. The value is in the
- * same range as the PIDInput values.
- *
- * @param t the absolute tolerance
- */
- public void setAbsoluteTolerance(double t) {
- m_controller.setAbsoluteTolerance(t);
- }
-
- /**
- * Set the percentage error which is considered tolerable for use with OnTarget. (Value of 15.0 ==
- * 15 percent).
- *
- * @param p the percent tolerance
- */
- public void setPercentTolerance(double p) {
- m_controller.setPercentTolerance(p);
- }
-
- /**
- * Return true if the error is within the percentage of the total input range, determined by
- * setTolerance. This assumes that the maximum and minimum input were set using setInput.
- *
- * @return true if the error is less than the tolerance
- */
- public boolean onTarget() {
- return m_controller.onTarget();
- }
-
- /**
- * Returns the input for the pid loop.
- *
- *
It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then it
- * should return the angle of the gyro.
- *
- *
All subclasses of {@link PIDSubsystem} must override this method.
- *
- * @return the value the pid loop should use as input
- */
- protected abstract double returnPIDInput();
-
- /**
- * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
- * This method is a good time to set motor values, maybe something along the lines of
- * driveline.tankDrive(output, -output).
- *
- *
All subclasses of {@link PIDSubsystem} must override this method.
- *
- * @param output the value the pid loop calculated
- */
- protected abstract void usePIDOutput(double output);
-
- /** Enables the internal {@link PIDController}. */
- public void enable() {
- m_controller.enable();
- }
-
- /** Disables the internal {@link PIDController}. */
- public void disable() {
- m_controller.disable();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
deleted file mode 100644
index d8cbd9dc66..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link PrintCommand} is a command which prints out a string when it is initialized, and then
- * immediately finishes. It is useful if you want a {@link CommandGroup} to print out a string when
- * it reaches a certain point.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class PrintCommand extends InstantCommand {
- /** The message to print out. */
- private final String m_message;
-
- /**
- * Instantiates a {@link PrintCommand} which will print the given message when it is run.
- *
- * @param message the message to print
- */
- public PrintCommand(String message) {
- super("Print(\"" + message + "\"");
- m_message = message;
- }
-
- @Override
- protected void initialize() {
- System.out.println(m_message);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
deleted file mode 100644
index 351ae99ce3..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
+++ /dev/null
@@ -1,347 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.hal.FRCNetComm.tInstances;
-import edu.wpi.first.hal.FRCNetComm.tResourceType;
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.networktables.NTSendable;
-import edu.wpi.first.networktables.NTSendableBuilder;
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler;
-import edu.wpi.first.wpilibj.livewindow.LiveWindow;
-import java.util.Enumeration;
-import java.util.Hashtable;
-import java.util.Map;
-import java.util.Vector;
-
-/**
- * The {@link Scheduler} is a singleton which holds the top-level running commands. It is in charge
- * of both calling the command's {@link Command#run() run()} method and to make sure that there are
- * no two commands with conflicting requirements running.
- *
- *
It is fine if teams wish to take control of the {@link Scheduler} themselves, all that needs
- * to be done is to call {@link Scheduler#getInstance() Scheduler.getInstance()}.{@link
- * Scheduler#run() run()} often to have {@link Command Commands} function correctly. However, this
- * is already done for you if you use the CommandBased Robot template.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see Command
- */
-public final class Scheduler implements NTSendable, AutoCloseable {
- /** The Singleton Instance. */
- private static Scheduler instance;
-
- /**
- * Returns the {@link Scheduler}, creating it if one does not exist.
- *
- * @return the {@link Scheduler}
- */
- public static synchronized Scheduler getInstance() {
- if (instance == null) {
- instance = new Scheduler();
- }
- return instance;
- }
-
- /** A hashtable of active {@link Command Commands} to their {@link LinkedListElement}. */
- private final Map m_commandTable = new Hashtable<>();
- /** The {@link Set} of all {@link Subsystem Subsystems}. */
- private final Set m_subsystems = new Set();
- /** The first {@link Command} in the list. */
- private LinkedListElement m_firstCommand;
- /** The last {@link Command} in the list. */
- private LinkedListElement m_lastCommand;
- /** Whether or not we are currently adding a command. */
- private boolean m_adding;
- /** Whether or not we are currently disabled. */
- private boolean m_disabled;
- /** A list of all {@link Command Commands} which need to be added. */
- @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
- private final Vector m_additions = new Vector<>();
- /**
- * A list of all {@link edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler Buttons}. It is
- * created lazily.
- */
- private Vector m_buttons;
-
- private boolean m_runningCommandsChanged;
-
- /** Instantiates a {@link Scheduler}. */
- private Scheduler() {
- HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
- SendableRegistry.addLW(this, "Scheduler");
- LiveWindow.setEnabledListener(
- () -> {
- disable();
- removeAll();
- });
- LiveWindow.setDisabledListener(
- () -> {
- enable();
- });
- }
-
- @Override
- public void close() {
- SendableRegistry.remove(this);
- LiveWindow.setEnabledListener(null);
- LiveWindow.setDisabledListener(null);
- }
-
- /**
- * Adds the command to the {@link Scheduler}. This will not add the {@link Command} immediately,
- * but will instead wait for the proper time in the {@link Scheduler#run()} loop before doing so.
- * The command returns immediately and does nothing if given null.
- *
- * Adding a {@link Command} to the {@link Scheduler} involves the {@link Scheduler} removing
- * any {@link Command} which has shared requirements.
- *
- * @param command the command to add
- */
- public void add(Command command) {
- if (command != null) {
- m_additions.addElement(command);
- }
- }
-
- /**
- * Adds a button to the {@link Scheduler}. The {@link Scheduler} will poll the button during its
- * {@link Scheduler#run()}.
- *
- * @param button the button to add
- */
- @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
- public void addButton(ButtonScheduler button) {
- if (m_buttons == null) {
- m_buttons = new Vector<>();
- }
- m_buttons.addElement(button);
- }
-
- /**
- * Adds a command immediately to the {@link Scheduler}. This should only be called in the {@link
- * Scheduler#run()} loop. Any command with conflicting requirements will be removed, unless it is
- * uninterruptible. Giving null does nothing.
- *
- * @param command the {@link Command} to add
- */
- @SuppressWarnings("MethodName")
- private void _add(Command command) {
- if (command == null) {
- return;
- }
-
- // Check to make sure no adding during adding
- if (m_adding) {
- System.err.println("WARNING: Can not start command from cancel method. Ignoring:" + command);
- return;
- }
-
- // Only add if not already in
- if (!m_commandTable.containsKey(command)) {
- // Check that the requirements can be had
- Enumeration> requirements = command.getRequirements();
- while (requirements.hasMoreElements()) {
- Subsystem lock = (Subsystem) requirements.nextElement();
- if (lock.getCurrentCommand() != null && !lock.getCurrentCommand().isInterruptible()) {
- return;
- }
- }
-
- // Give it the requirements
- m_adding = true;
- requirements = command.getRequirements();
- while (requirements.hasMoreElements()) {
- Subsystem lock = (Subsystem) requirements.nextElement();
- if (lock.getCurrentCommand() != null) {
- lock.getCurrentCommand().cancel();
- remove(lock.getCurrentCommand());
- }
- lock.setCurrentCommand(command);
- }
- m_adding = false;
-
- // Add it to the list
- LinkedListElement element = new LinkedListElement();
- element.setData(command);
- if (m_firstCommand == null) {
- m_firstCommand = m_lastCommand = element;
- } else {
- m_lastCommand.add(element);
- m_lastCommand = element;
- }
- m_commandTable.put(command, element);
-
- m_runningCommandsChanged = true;
-
- command.startRunning();
- }
- }
-
- /**
- * Runs a single iteration of the loop. This method should be called often in order to have a
- * functioning {@link Command} system. The loop has five stages:
- *
- *
- * - Poll the Buttons
- *
- Execute/Remove the Commands
- *
- Send values to SmartDashboard
- *
- Add Commands
- *
- Add Defaults
- *
- */
- public void run() {
- m_runningCommandsChanged = false;
-
- if (m_disabled) {
- return;
- } // Don't run when m_disabled
-
- // Get button input (going backwards preserves button priority)
- if (m_buttons != null) {
- for (int i = m_buttons.size() - 1; i >= 0; i--) {
- m_buttons.elementAt(i).execute();
- }
- }
-
- // Call every subsystem's periodic method
- Enumeration> subsystems = m_subsystems.getElements();
- while (subsystems.hasMoreElements()) {
- ((Subsystem) subsystems.nextElement()).periodic();
- }
-
- // Loop through the commands
- LinkedListElement element = m_firstCommand;
- while (element != null) {
- Command command = element.getData();
- element = element.getNext();
- if (!command.run()) {
- remove(command);
- m_runningCommandsChanged = true;
- }
- }
-
- // Add the new things
- for (int i = 0; i < m_additions.size(); i++) {
- _add(m_additions.elementAt(i));
- }
- m_additions.removeAllElements();
-
- // Add in the defaults
- Enumeration> locks = m_subsystems.getElements();
- while (locks.hasMoreElements()) {
- Subsystem lock = (Subsystem) locks.nextElement();
- if (lock.getCurrentCommand() == null) {
- _add(lock.getDefaultCommand());
- }
- lock.confirmCommand();
- }
- }
-
- /**
- * Registers a {@link Subsystem} to this {@link Scheduler}, so that the {@link Scheduler} might
- * know if a default {@link Command} needs to be run. All {@link Subsystem Subsystems} should call
- * this.
- *
- * @param system the system
- */
- void registerSubsystem(Subsystem system) {
- if (system != null) {
- m_subsystems.add(system);
- }
- }
-
- /**
- * Removes the {@link Command} from the {@link Scheduler}.
- *
- * @param command the command to remove
- */
- void remove(Command command) {
- if (command == null || !m_commandTable.containsKey(command)) {
- return;
- }
- LinkedListElement element = m_commandTable.get(command);
- m_commandTable.remove(command);
-
- if (element.equals(m_lastCommand)) {
- m_lastCommand = element.getPrevious();
- }
- if (element.equals(m_firstCommand)) {
- m_firstCommand = element.getNext();
- }
- element.remove();
-
- Enumeration> requirements = command.getRequirements();
- while (requirements.hasMoreElements()) {
- ((Subsystem) requirements.nextElement()).setCurrentCommand(null);
- }
-
- command.removed();
- }
-
- /** Removes all commands. */
- public void removeAll() {
- // TODO: Confirm that this works with "uninteruptible" commands
- while (m_firstCommand != null) {
- remove(m_firstCommand.getData());
- }
- }
-
- /** Disable the command scheduler. */
- public void disable() {
- m_disabled = true;
- }
-
- /** Enable the command scheduler. */
- public void enable() {
- m_disabled = false;
- }
-
- @Override
- public void initSendable(NTSendableBuilder builder) {
- builder.setSmartDashboardType("Scheduler");
- final NetworkTableEntry namesEntry = builder.getEntry("Names");
- final NetworkTableEntry idsEntry = builder.getEntry("Ids");
- final NetworkTableEntry cancelEntry = builder.getEntry("Cancel");
- builder.setUpdateTable(
- () -> {
- if (namesEntry != null && idsEntry != null && cancelEntry != null) {
- // Get the commands to cancel
- double[] toCancel = cancelEntry.getDoubleArray(new double[0]);
- if (toCancel.length > 0) {
- for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
- for (double d : toCancel) {
- if (e.getData().hashCode() == d) {
- e.getData().cancel();
- }
- }
- }
- cancelEntry.setDoubleArray(new double[0]);
- }
-
- if (m_runningCommandsChanged) {
- // Set the the running commands
- int number = 0;
- for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
- number++;
- }
- String[] commands = new String[number];
- double[] ids = new double[number];
- number = 0;
- for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
- commands[number] = e.getData().getName();
- ids[number] = e.getData().hashCode();
- number++;
- }
- namesEntry.setStringArray(commands);
- idsEntry.setDoubleArray(ids);
- }
- }
- });
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java
deleted file mode 100644
index 91180eba53..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Set.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.Enumeration;
-import java.util.Vector;
-
-@SuppressWarnings("all")
-/**
- * A set.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Set {
- private Vector m_set = new Vector();
-
- public Set() {}
-
- public void add(Object o) {
- if (m_set.contains(o)) {
- return;
- }
- m_set.addElement(o);
- }
-
- public void add(Set s) {
- Enumeration stuff = s.getElements();
- for (Enumeration e = stuff; e.hasMoreElements(); ) {
- add(e.nextElement());
- }
- }
-
- public void clear() {
- m_set.clear();
- }
-
- public boolean contains(Object o) {
- return m_set.contains(o);
- }
-
- public Enumeration getElements() {
- return m_set.elements();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
deleted file mode 100644
index ba6cec416e..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link StartCommand} will call the {@link Command#start() start()} method of another command
- * when it is initialized and will finish immediately.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class StartCommand extends InstantCommand {
- /** The command to fork. */
- private final Command m_commandToFork;
-
- /**
- * Instantiates a {@link StartCommand} which will start the given command whenever its {@link
- * Command#initialize() initialize()} is called.
- *
- * @param commandToStart the {@link Command} to start
- */
- public StartCommand(Command commandToStart) {
- super("Start(" + commandToStart + ")");
- m_commandToFork = commandToStart;
- }
-
- @Override
- protected void initialize() {
- m_commandToFork.start();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
deleted file mode 100644
index df5984b572..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
+++ /dev/null
@@ -1,237 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.util.sendable.SendableRegistry;
-import java.util.Collections;
-
-/**
- * This class defines a major component of the robot.
- *
- *
A good example of a subsystem is the drivetrain, or a claw if the robot has one.
- *
- *
All motors should be a part of a subsystem. For instance, all the wheel motors should be a
- * part of some kind of "Drivetrain" subsystem.
- *
- *
Subsystems are used within the command system as requirements for {@link Command}. Only one
- * command which requires a subsystem can run at a time. Also, subsystems can have default commands
- * which are started if there is no command running which requires this subsystem.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see Command
- */
-public abstract class Subsystem implements Sendable, AutoCloseable {
- /** Whether or not getDefaultCommand() was called. */
- private boolean m_initializedDefaultCommand;
- /** The current command. */
- private Command m_currentCommand;
-
- private boolean m_currentCommandChanged;
-
- /** The default command. */
- private Command m_defaultCommand;
-
- /**
- * Creates a subsystem with the given name.
- *
- * @param name the name of the subsystem
- */
- public Subsystem(String name) {
- SendableRegistry.addLW(this, name, name);
- Scheduler.getInstance().registerSubsystem(this);
- }
-
- /** Creates a subsystem. This will set the name to the name of the class. */
- public Subsystem() {
- String name = getClass().getName();
- name = name.substring(name.lastIndexOf('.') + 1);
- SendableRegistry.addLW(this, name, name);
- Scheduler.getInstance().registerSubsystem(this);
- m_currentCommandChanged = true;
- }
-
- @Override
- public void close() {
- SendableRegistry.remove(this);
- }
-
- /**
- * Initialize the default command for a subsystem By default subsystems have no default command,
- * but if they do, the default command is set with this method. It is called on all Subsystems by
- * CommandBase in the users program after all the Subsystems are created.
- */
- protected abstract void initDefaultCommand();
-
- /** When the run method of the scheduler is called this method will be called. */
- public void periodic() {
- // Override me!
- }
-
- /**
- * Sets the default command. If this is not called or is called with null, then there will be no
- * default command for the subsystem.
- *
- *
WARNING: This should NOT be called in a constructor if the subsystem is a
- * singleton.
- *
- * @param command the default command (or null if there should be none)
- * @throws IllegalUseOfCommandException if the command does not require the subsystem
- */
- public void setDefaultCommand(Command command) {
- if (command == null) {
- m_defaultCommand = null;
- } else {
- if (!Collections.list(command.getRequirements()).contains(this)) {
- throw new IllegalUseOfCommandException("A default command must require the subsystem");
- }
- m_defaultCommand = command;
- }
- }
-
- /**
- * Returns the default command (or null if there is none).
- *
- * @return the default command
- */
- public Command getDefaultCommand() {
- if (!m_initializedDefaultCommand) {
- m_initializedDefaultCommand = true;
- initDefaultCommand();
- }
- return m_defaultCommand;
- }
-
- /**
- * Returns the default command name, or empty string is there is none.
- *
- * @return the default command name
- */
- public String getDefaultCommandName() {
- Command defaultCommand = getDefaultCommand();
- if (defaultCommand != null) {
- return defaultCommand.getName();
- } else {
- return "";
- }
- }
-
- /**
- * Sets the current command.
- *
- * @param command the new current command
- */
- void setCurrentCommand(Command command) {
- m_currentCommand = command;
- m_currentCommandChanged = true;
- }
-
- /**
- * Call this to alert Subsystem that the current command is actually the command. Sometimes, the
- * {@link Subsystem} is told that it has no command while the {@link Scheduler} is going through
- * the loop, only to be soon after given a new one. This will avoid that situation.
- */
- void confirmCommand() {
- if (m_currentCommandChanged) {
- m_currentCommandChanged = false;
- }
- }
-
- /**
- * Returns the command which currently claims this subsystem.
- *
- * @return the command which currently claims this subsystem
- */
- public Command getCurrentCommand() {
- return m_currentCommand;
- }
-
- /**
- * Returns the current command name, or empty string if no current command.
- *
- * @return the current command name
- */
- public String getCurrentCommandName() {
- Command currentCommand = getCurrentCommand();
- if (currentCommand != null) {
- return currentCommand.getName();
- } else {
- return "";
- }
- }
-
- /**
- * Associate a {@link Sendable} with this Subsystem. Also update the child's name.
- *
- * @param name name to give child
- * @param child sendable
- */
- public void addChild(String name, Sendable child) {
- SendableRegistry.addLW(child, getSubsystem(), name);
- }
-
- /**
- * Associate a {@link Sendable} with this Subsystem.
- *
- * @param child sendable
- */
- public void addChild(Sendable child) {
- SendableRegistry.setSubsystem(child, getSubsystem());
- SendableRegistry.enableLiveWindow(child);
- }
-
- /**
- * Gets the name of this Subsystem.
- *
- * @return Name
- */
- public String getName() {
- return SendableRegistry.getName(this);
- }
-
- /**
- * Sets the name of this Subsystem.
- *
- * @param name name
- */
- public void setName(String name) {
- SendableRegistry.setName(this, name);
- }
-
- /**
- * Gets the subsystem name of this Subsystem.
- *
- * @return Subsystem name
- */
- public String getSubsystem() {
- return SendableRegistry.getSubsystem(this);
- }
-
- /**
- * Sets the subsystem name of this Subsystem.
- *
- * @param subsystem subsystem name
- */
- public void setSubsystem(String subsystem) {
- SendableRegistry.setSubsystem(this, subsystem);
- }
-
- @Override
- public String toString() {
- return getSubsystem();
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- builder.setSmartDashboardType("Subsystem");
-
- builder.addBooleanProperty(".hasDefault", () -> m_defaultCommand != null, null);
- builder.addStringProperty(".default", this::getDefaultCommandName, null);
- builder.addBooleanProperty(".hasCommand", () -> m_currentCommand != null, null);
- builder.addStringProperty(".command", this::getCurrentCommandName, null);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
deleted file mode 100644
index 70fb087350..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
+++ /dev/null
@@ -1,59 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link TimedCommand} will wait for a timeout before finishing. {@link TimedCommand} is used to
- * execute a command for a given amount of time.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class TimedCommand extends Command {
- /**
- * Instantiates a TimedCommand with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time the command takes to run (seconds)
- */
- public TimedCommand(String name, double timeout) {
- super(name, timeout);
- }
-
- /**
- * Instantiates a TimedCommand with the given timeout.
- *
- * @param timeout the time the command takes to run (seconds)
- */
- public TimedCommand(double timeout) {
- super(timeout);
- }
-
- /**
- * Instantiates a TimedCommand with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time the command takes to run (seconds)
- * @param subsystem the subsystem that this command requires
- */
- public TimedCommand(String name, double timeout, Subsystem subsystem) {
- super(name, timeout, subsystem);
- }
-
- /**
- * Instantiates a TimedCommand with the given timeout.
- *
- * @param timeout the time the command takes to run (seconds)
- * @param subsystem the subsystem that this command requires
- */
- public TimedCommand(double timeout, Subsystem subsystem) {
- super(timeout, subsystem);
- }
-
- /** Ends command when timed out. */
- @Override
- protected boolean isFinished() {
- return isTimedOut();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
deleted file mode 100644
index b19a959573..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A {@link WaitCommand} will wait for a certain amount of time before finishing. It is useful if
- * you want a {@link CommandGroup} to pause for a moment.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @see CommandGroup
- */
-public class WaitCommand extends TimedCommand {
- /**
- * Instantiates a {@link WaitCommand} with the given timeout.
- *
- * @param timeout the time the command takes to run (seconds)
- */
- public WaitCommand(double timeout) {
- this("Wait(" + timeout + ")", timeout);
- }
-
- /**
- * Instantiates a {@link WaitCommand} with the given timeout.
- *
- * @param name the name of the command
- * @param timeout the time the command takes to run (seconds)
- */
- public WaitCommand(String name, double timeout) {
- super(name, timeout);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
deleted file mode 100644
index 5b24c5a9e4..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * This command will only finish if whatever {@link CommandGroup} it is in has no active children.
- * If it is not a part of a {@link CommandGroup}, then it will finish immediately. If it is itself
- * an active child, then the {@link CommandGroup} will never end.
- *
- *
This class is useful for the situation where you want to allow anything running in parallel to
- * finish, before continuing in the main {@link CommandGroup} sequence.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class WaitForChildren extends Command {
- @Override
- protected boolean isFinished() {
- return getGroup() == null || getGroup().m_children.isEmpty();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
deleted file mode 100644
index 7f617ebc7c..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.Timer;
-
-/**
- * WaitUntilCommand - waits until an absolute game time. This will wait until the game clock reaches
- * some value, then continue to the next command.
- *
- *
This class is provided by the OldCommands VendorDep
- */
-public class WaitUntilCommand extends Command {
- private final double m_time;
-
- public WaitUntilCommand(double time) {
- super("WaitUntil(" + time + ")");
- m_time = time;
- }
-
- /** Check if we've reached the actual finish time. */
- @Override
- public boolean isFinished() {
- return Timer.getMatchTime() >= m_time;
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java
deleted file mode 100644
index 22a0611e87..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogAccelerometer.java
+++ /dev/null
@@ -1,51 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogAccelerometer;
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogAccelerometer for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogAccelerometer extends AnalogAccelerometer implements PIDSource {
- protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDAnalogAccelerometer(int channel) {
- super(channel);
- }
-
- public PIDAnalogAccelerometer(AnalogInput channel) {
- super(channel);
- }
-
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Get the Acceleration for the PID Source parent.
- *
- * @return The current acceleration in Gs.
- */
- @Override
- public double pidGet() {
- return getAcceleration();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java
deleted file mode 100644
index 9881657606..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogGyro.java
+++ /dev/null
@@ -1,73 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogGyro;
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogGyro for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogGyro extends AnalogGyro implements PIDSource {
- private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDAnalogGyro(int channel) {
- super(channel);
- }
-
- public PIDAnalogGyro(AnalogInput channel) {
- super(channel);
- }
-
- public PIDAnalogGyro(int channel, int center, double offset) {
- super(channel, center, offset);
- }
-
- public PIDAnalogGyro(AnalogInput channel, int center, double offset) {
- super(channel, center, offset);
- }
-
- /**
- * Set which parameter of the gyro you are using as a process control variable. The Gyro class
- * supports the rate and displacement parameters
- *
- * @param pidSource An enum to select the parameter.
- */
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Get the output of the gyro for use with PIDControllers. May be the angle or rate depending on
- * the set PIDSourceType
- *
- * @return the output according to the gyro
- */
- @Override
- public double pidGet() {
- switch (m_pidSource) {
- case kRate:
- return getRate();
- case kDisplacement:
- return getAngle();
- default:
- return 0.0;
- }
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java
deleted file mode 100644
index 797be71d39..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogInput.java
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogInput for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogInput extends AnalogInput implements PIDSource {
- protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDAnalogInput(int channel) {
- super(channel);
- }
-
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Get the average voltage for use with PIDController.
- *
- * @return the average voltage
- */
- @Override
- public double pidGet() {
- return getAverageVoltage();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java
deleted file mode 100644
index f905e5a6e7..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDAnalogPotentiometer.java
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.AnalogPotentiometer;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogPotentiometer for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDAnalogPotentiometer extends AnalogPotentiometer implements PIDSource {
- protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDAnalogPotentiometer(int channel, double fullRange, double offset) {
- super(channel, fullRange, offset);
- }
-
- public PIDAnalogPotentiometer(AnalogInput input, double fullRange, double offset) {
- super(input, fullRange, offset);
- }
-
- public PIDAnalogPotentiometer(int channel, double scale) {
- super(channel, scale);
- }
-
- public PIDAnalogPotentiometer(AnalogInput input, double scale) {
- super(input, scale);
- }
-
- public PIDAnalogPotentiometer(int channel) {
- super(channel);
- }
-
- public PIDAnalogPotentiometer(AnalogInput input) {
- super(input);
- }
-
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- if (!pidSource.equals(PIDSourceType.kDisplacement)) {
- throw new IllegalArgumentException("Only displacement PID is allowed for potentiometers.");
- }
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Implement the PIDSource interface.
- *
- * @return The current reading.
- */
- @Override
- public double pidGet() {
- return get();
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java
deleted file mode 100644
index 67c3ed198b..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDEncoder.java
+++ /dev/null
@@ -1,109 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.DigitalSource;
-import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-
-/**
- * Wrapper so that PIDSource is implemented for Encoder for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDEncoder extends Encoder implements PIDSource {
- private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDEncoder(final int channelA, final int channelB, boolean reverseDirection) {
- super(channelA, channelB, reverseDirection, EncodingType.k4X);
- }
-
- public PIDEncoder(final int channelA, final int channelB) {
- super(channelA, channelB, false);
- }
-
- public PIDEncoder(
- final int channelA,
- final int channelB,
- boolean reverseDirection,
- final EncodingType encodingType) {
- super(channelA, channelB, reverseDirection, encodingType);
- }
-
- public PIDEncoder(
- final int channelA, final int channelB, final int indexChannel, boolean reverseDirection) {
- super(channelA, channelB, indexChannel, reverseDirection);
- }
-
- public PIDEncoder(final int channelA, final int channelB, final int indexChannel) {
- super(channelA, channelB, indexChannel, false);
- }
-
- public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection) {
- super(sourceA, sourceB, reverseDirection, EncodingType.k4X);
- }
-
- public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB) {
- super(sourceA, sourceB, false);
- }
-
- public PIDEncoder(
- DigitalSource sourceA,
- DigitalSource sourceB,
- boolean reverseDirection,
- final EncodingType encodingType) {
- super(sourceA, sourceB, reverseDirection, encodingType);
- }
-
- public PIDEncoder(
- DigitalSource sourceA,
- DigitalSource sourceB,
- DigitalSource indexSource,
- boolean reverseDirection) {
- super(sourceA, sourceB, indexSource, reverseDirection);
- }
-
- public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource) {
- super(sourceA, sourceB, indexSource, false);
- }
-
- /**
- * Set which parameter of the encoder you are using as a process control variable. The encoder
- * class supports the rate and distance parameters.
- *
- * @param pidSource An enum to select the parameter.
- */
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Implement the PIDSource interface.
- *
- * @return The current value of the selected source parameter.
- */
- @Override
- public double pidGet() {
- switch (m_pidSource) {
- case kDisplacement:
- return getDistance();
- case kRate:
- return getRate();
- default:
- return 0.0;
- }
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java
deleted file mode 100644
index 11d033bb2c..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDMotorController.java
+++ /dev/null
@@ -1,116 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.util.sendable.SendableBuilder;
-import edu.wpi.first.wpilibj.PIDOutput;
-import edu.wpi.first.wpilibj.motorcontrol.MotorController;
-
-/**
- * Wrapper so that PIDOutput is implemented for MotorController for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDMotorController implements PIDOutput, MotorController, Sendable {
- private final MotorController m_motorController;
-
- public PIDMotorController(MotorController motorController) {
- m_motorController = motorController;
- }
-
- /**
- * Write out the PID value as seen in the PIDOutput base object.
- *
- * @param output Write out the PWM value as was found in the PIDController
- */
- @Override
- public void pidWrite(double output) {
- m_motorController.set(output);
- }
-
- /**
- * Common interface for setting the speed of a motor controller.
- *
- * @param speed The speed to set. Value should be between -1.0 and 1.0.
- */
- @Override
- public void set(double speed) {
- m_motorController.set(speed);
- }
-
- /**
- * Sets the voltage output of the MotorController. Compensates for the current bus voltage to
- * ensure that the desired voltage is output even if the battery voltage is below 12V - highly
- * useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
- * calculation).
- *
- *
NOTE: This function *must* be called regularly in order for voltage compensation to work
- * properly - unlike the ordinary set function, it is not "set it and forget it."
- *
- * @param outputVolts The voltage to output.
- */
- @Override
- public void setVoltage(double outputVolts) {
- m_motorController.setVoltage(outputVolts);
- }
-
- /**
- * Common interface for getting the current set speed of a motor controller.
- *
- * @return The current set speed. Value is between -1.0 and 1.0.
- */
- @Override
- public double get() {
- return m_motorController.get();
- }
-
- /**
- * Common interface for inverting direction of a motor controller.
- *
- * @param isInverted The state of inversion true is inverted.
- */
- @Override
- public void setInverted(boolean isInverted) {
- m_motorController.setInverted(isInverted);
- }
-
- /**
- * Common interface for returning if a motor controller is in the inverted state or not.
- *
- * @return isInverted The state of the inversion true is inverted.
- */
- @Override
- public boolean getInverted() {
- return m_motorController.getInverted();
- }
-
- /** Disable the motor controller. */
- @Override
- public void disable() {
- m_motorController.disable();
- }
-
- /**
- * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
- * motor.
- */
- @Override
- public void stopMotor() {
- m_motorController.stopMotor();
- }
-
- @Override
- public void initSendable(SendableBuilder builder) {
- builder.setSmartDashboardType("Motor Controller");
- builder.setActuator(true);
- builder.setSafeState(this::disable);
- builder.addDoubleProperty("Value", this::get, this::set);
- }
-}
diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java
deleted file mode 100644
index e542b6825d..0000000000
--- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/pidwrappers/PIDUltrasonic.java
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.pidwrappers;
-
-import edu.wpi.first.wpilibj.DigitalInput;
-import edu.wpi.first.wpilibj.DigitalOutput;
-import edu.wpi.first.wpilibj.PIDSource;
-import edu.wpi.first.wpilibj.PIDSourceType;
-import edu.wpi.first.wpilibj.Ultrasonic;
-
-/**
- * Wrapper so that PIDSource is implemented for Ultrasonic for old PIDController.
- *
- *
This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
- * wrapper.
- */
-@Deprecated(since = "2022", forRemoval = true)
-public class PIDUltrasonic extends Ultrasonic implements PIDSource {
- protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
-
- public PIDUltrasonic(int pingChannel, int echoChannel) {
- super(pingChannel, echoChannel);
- }
-
- public PIDUltrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
- super(pingChannel, echoChannel);
- }
-
- @Override
- public void setPIDSourceType(PIDSourceType pidSource) {
- if (!pidSource.equals(PIDSourceType.kDisplacement)) {
- throw new IllegalArgumentException("Only displacement PID is allowed for ultrasonics.");
- }
- m_pidSource = pidSource;
- }
-
- @Override
- public PIDSourceType getPIDSourceType() {
- return m_pidSource;
- }
-
- /**
- * Get the range in the inches for the PIDSource base object.
- *
- * @return The range in inches
- */
- @Override
- public double pidGet() {
- return getRangeInches();
- }
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp b/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp
deleted file mode 100644
index 825d4ebf83..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/PIDBase.cpp
+++ /dev/null
@@ -1,358 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDBase.h"
-
-#include
-#include
-
-#include
-#include
-#include
-
-#include "frc/PIDOutput.h"
-
-using namespace frc;
-
-template
-constexpr const T& clamp(const T& value, const T& low, const T& high) {
- return std::max(low, std::min(value, high));
-}
-
-PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source,
- PIDOutput& output)
- : PIDBase(Kp, Ki, Kd, 0.0, source, output) {}
-
-PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
- PIDOutput& output) {
- m_P = Kp;
- m_I = Ki;
- m_D = Kd;
- m_F = Kf;
-
- m_pidInput = &source;
- m_filter = LinearFilter::MovingAverage(1);
-
- m_pidOutput = &output;
-
- m_setpointTimer.Start();
-
- static int instances = 0;
- instances++;
- HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
- wpi::SendableRegistry::Add(this, "PIDController", instances);
-}
-
-double PIDBase::Get() const {
- std::scoped_lock lock(m_thisMutex);
- return m_result;
-}
-
-void PIDBase::SetContinuous(bool continuous) {
- std::scoped_lock lock(m_thisMutex);
- m_continuous = continuous;
-}
-
-void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
- {
- std::scoped_lock lock(m_thisMutex);
- m_minimumInput = minimumInput;
- m_maximumInput = maximumInput;
- m_inputRange = maximumInput - minimumInput;
- }
-
- SetSetpoint(m_setpoint);
-}
-
-void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
- std::scoped_lock lock(m_thisMutex);
- m_minimumOutput = minimumOutput;
- m_maximumOutput = maximumOutput;
-}
-
-void PIDBase::SetPID(double p, double i, double d) {
- {
- std::scoped_lock lock(m_thisMutex);
- m_P = p;
- m_I = i;
- m_D = d;
- }
-}
-
-void PIDBase::SetPID(double p, double i, double d, double f) {
- std::scoped_lock lock(m_thisMutex);
- m_P = p;
- m_I = i;
- m_D = d;
- m_F = f;
-}
-
-void PIDBase::SetP(double p) {
- std::scoped_lock lock(m_thisMutex);
- m_P = p;
-}
-
-void PIDBase::SetI(double i) {
- std::scoped_lock lock(m_thisMutex);
- m_I = i;
-}
-
-void PIDBase::SetD(double d) {
- std::scoped_lock lock(m_thisMutex);
- m_D = d;
-}
-
-void PIDBase::SetF(double f) {
- std::scoped_lock lock(m_thisMutex);
- m_F = f;
-}
-
-double PIDBase::GetP() const {
- std::scoped_lock lock(m_thisMutex);
- return m_P;
-}
-
-double PIDBase::GetI() const {
- std::scoped_lock lock(m_thisMutex);
- return m_I;
-}
-
-double PIDBase::GetD() const {
- std::scoped_lock lock(m_thisMutex);
- return m_D;
-}
-
-double PIDBase::GetF() const {
- std::scoped_lock lock(m_thisMutex);
- return m_F;
-}
-
-void PIDBase::SetSetpoint(double setpoint) {
- {
- std::scoped_lock lock(m_thisMutex);
-
- if (m_maximumInput > m_minimumInput) {
- if (setpoint > m_maximumInput) {
- m_setpoint = m_maximumInput;
- } else if (setpoint < m_minimumInput) {
- m_setpoint = m_minimumInput;
- } else {
- m_setpoint = setpoint;
- }
- } else {
- m_setpoint = setpoint;
- }
- }
-}
-
-double PIDBase::GetSetpoint() const {
- std::scoped_lock lock(m_thisMutex);
- return m_setpoint;
-}
-
-double PIDBase::GetDeltaSetpoint() const {
- std::scoped_lock lock(m_thisMutex);
- return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get().value();
-}
-
-double PIDBase::GetError() const {
- double setpoint = GetSetpoint();
- {
- std::scoped_lock lock(m_thisMutex);
- return GetContinuousError(setpoint - m_pidInput->PIDGet());
- }
-}
-
-double PIDBase::GetAvgError() const {
- return GetError();
-}
-
-void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
- m_pidInput->SetPIDSourceType(pidSource);
-}
-
-PIDSourceType PIDBase::GetPIDSourceType() const {
- return m_pidInput->GetPIDSourceType();
-}
-
-void PIDBase::SetTolerance(double percent) {
- std::scoped_lock lock(m_thisMutex);
- m_toleranceType = kPercentTolerance;
- m_tolerance = percent;
-}
-
-void PIDBase::SetAbsoluteTolerance(double absTolerance) {
- std::scoped_lock lock(m_thisMutex);
- m_toleranceType = kAbsoluteTolerance;
- m_tolerance = absTolerance;
-}
-
-void PIDBase::SetPercentTolerance(double percent) {
- std::scoped_lock lock(m_thisMutex);
- m_toleranceType = kPercentTolerance;
- m_tolerance = percent;
-}
-
-void PIDBase::SetToleranceBuffer(int bufLength) {
- std::scoped_lock lock(m_thisMutex);
- m_filter = LinearFilter::MovingAverage(bufLength);
-}
-
-bool PIDBase::OnTarget() const {
- double error = GetError();
-
- std::scoped_lock lock(m_thisMutex);
- switch (m_toleranceType) {
- case kPercentTolerance:
- return std::fabs(error) < m_tolerance / 100 * m_inputRange;
- break;
- case kAbsoluteTolerance:
- return std::fabs(error) < m_tolerance;
- break;
- case kNoTolerance:
- // TODO: this case needs an error
- return false;
- }
- return false;
-}
-
-void PIDBase::Reset() {
- std::scoped_lock lock(m_thisMutex);
- m_prevError = 0;
- m_totalError = 0;
- m_result = 0;
-}
-
-void PIDBase::PIDWrite(double output) {
- SetSetpoint(output);
-}
-
-void PIDBase::InitSendable(wpi::SendableBuilder& builder) {
- builder.SetSmartDashboardType("PIDController");
- builder.SetSafeState([=] { Reset(); });
- builder.AddDoubleProperty(
- "p", [=] { return GetP(); }, [=](double value) { SetP(value); });
- builder.AddDoubleProperty(
- "i", [=] { return GetI(); }, [=](double value) { SetI(value); });
- builder.AddDoubleProperty(
- "d", [=] { return GetD(); }, [=](double value) { SetD(value); });
- builder.AddDoubleProperty(
- "f", [=] { return GetF(); }, [=](double value) { SetF(value); });
- builder.AddDoubleProperty(
- "setpoint", [=] { return GetSetpoint(); },
- [=](double value) { SetSetpoint(value); });
-}
-
-void PIDBase::Calculate() {
- if (m_pidInput == nullptr || m_pidOutput == nullptr) {
- return;
- }
-
- bool enabled;
- {
- std::scoped_lock lock(m_thisMutex);
- enabled = m_enabled;
- }
-
- if (enabled) {
- double input;
-
- // Storage for function inputs
- PIDSourceType pidSourceType;
- double P;
- double I;
- double D;
- double feedForward = CalculateFeedForward();
- double minimumOutput;
- double maximumOutput;
-
- // Storage for function input-outputs
- double prevError;
- double error;
- double totalError;
-
- {
- std::scoped_lock lock(m_thisMutex);
-
- input = m_filter.Calculate(m_pidInput->PIDGet());
-
- pidSourceType = m_pidInput->GetPIDSourceType();
- P = m_P;
- I = m_I;
- D = m_D;
- minimumOutput = m_minimumOutput;
- maximumOutput = m_maximumOutput;
-
- prevError = m_prevError;
- error = GetContinuousError(m_setpoint - input);
- totalError = m_totalError;
- }
-
- // Storage for function outputs
- double result;
-
- if (pidSourceType == PIDSourceType::kRate) {
- if (P != 0) {
- totalError =
- clamp(totalError + error, minimumOutput / P, maximumOutput / P);
- }
-
- result = D * error + P * totalError + feedForward;
- } else {
- if (I != 0) {
- totalError =
- clamp(totalError + error, minimumOutput / I, maximumOutput / I);
- }
-
- result =
- P * error + I * totalError + D * (error - prevError) + feedForward;
- }
-
- result = clamp(result, minimumOutput, maximumOutput);
-
- {
- // Ensures m_enabled check and PIDWrite() call occur atomically
- std::scoped_lock pidWriteLock(m_pidWriteMutex);
- std::unique_lock mainLock(m_thisMutex);
- if (m_enabled) {
- // Don't block other PIDBase operations on PIDWrite()
- mainLock.unlock();
-
- m_pidOutput->PIDWrite(result);
- }
- }
-
- std::scoped_lock lock(m_thisMutex);
- m_prevError = m_error;
- m_error = error;
- m_totalError = totalError;
- m_result = result;
- }
-}
-
-double PIDBase::CalculateFeedForward() {
- if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
- return m_F * GetSetpoint();
- } else {
- double temp = m_F * GetDeltaSetpoint();
- m_prevSetpoint = m_setpoint;
- m_setpointTimer.Reset();
- return temp;
- }
-}
-
-double PIDBase::GetContinuousError(double error) const {
- if (m_continuous && m_inputRange != 0) {
- error = std::fmod(error, m_inputRange);
- if (std::fabs(error) > m_inputRange / 2) {
- if (error > 0) {
- return error - m_inputRange;
- } else {
- return error + m_inputRange;
- }
- }
- }
-
- return error;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/PIDController.cpp b/wpilibOldCommands/src/main/native/cpp/PIDController.cpp
deleted file mode 100644
index ee8382c1ef..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/PIDController.cpp
+++ /dev/null
@@ -1,84 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDController.h"
-
-#include
-
-#include "frc/Notifier.h"
-#include "frc/PIDOutput.h"
-
-using namespace frc;
-
-PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
- PIDOutput* output, double period)
- : PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
- PIDSource* source, PIDOutput* output,
- double period)
- : PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
- PIDOutput& output, double period)
- : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
-
-PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
- PIDSource& source, PIDOutput& output,
- double period)
- : PIDBase(Kp, Ki, Kd, Kf, source, output) {
- m_controlLoop = std::make_unique(&PIDController::Calculate, this);
- m_controlLoop->StartPeriodic(units::second_t(period));
-}
-
-PIDController::~PIDController() {
- // Forcefully stopping the notifier so the callback can successfully run.
- m_controlLoop->Stop();
-}
-
-void PIDController::Enable() {
- {
- std::scoped_lock lock(m_thisMutex);
- m_enabled = true;
- }
-}
-
-void PIDController::Disable() {
- {
- // Ensures m_enabled modification and PIDWrite() call occur atomically
- std::scoped_lock pidWriteLock(m_pidWriteMutex);
- {
- std::scoped_lock mainLock(m_thisMutex);
- m_enabled = false;
- }
-
- m_pidOutput->PIDWrite(0);
- }
-}
-
-void PIDController::SetEnabled(bool enable) {
- if (enable) {
- Enable();
- } else {
- Disable();
- }
-}
-
-bool PIDController::IsEnabled() const {
- std::scoped_lock lock(m_thisMutex);
- return m_enabled;
-}
-
-void PIDController::Reset() {
- Disable();
-
- PIDBase::Reset();
-}
-
-void PIDController::InitSendable(wpi::SendableBuilder& builder) {
- PIDBase::InitSendable(builder);
- builder.AddBooleanProperty(
- "enabled", [=] { return IsEnabled(); },
- [=](bool value) { SetEnabled(value); });
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp b/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp
deleted file mode 100644
index 3a9e3ea88c..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/PIDSource.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/PIDSource.h"
-
-using namespace frc;
-
-void PIDSource::SetPIDSourceType(PIDSourceType pidSource) {
- m_pidSource = pidSource;
-}
-
-PIDSourceType PIDSource::GetPIDSourceType() const {
- return m_pidSource;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp
deleted file mode 100644
index ef2c03d12d..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/Button.cpp
+++ /dev/null
@@ -1,27 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/Button.h"
-
-using namespace frc;
-
-void Button::WhenPressed(Command* command) {
- WhenActive(command);
-}
-
-void Button::WhileHeld(Command* command) {
- WhileActive(command);
-}
-
-void Button::WhenReleased(Command* command) {
- WhenInactive(command);
-}
-
-void Button::CancelWhenPressed(Command* command) {
- CancelWhenActive(command);
-}
-
-void Button::ToggleWhenPressed(Command* command) {
- ToggleWhenActive(command);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp
deleted file mode 100644
index b210c8df5e..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/ButtonScheduler.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ButtonScheduler.h"
-
-#include "frc/commands/Scheduler.h"
-
-using namespace frc;
-
-ButtonScheduler::ButtonScheduler(bool last, Trigger* button, Command* orders)
- : m_pressedLast(last), m_button(button), m_command(orders) {}
-
-void ButtonScheduler::Start() {
- Scheduler::GetInstance()->AddButton(this);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
deleted file mode 100644
index faff376ec4..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/CancelButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-CancelButtonScheduler::CancelButtonScheduler(bool last, Trigger* button,
- Command* orders)
- : ButtonScheduler(last, button, orders) {}
-
-void CancelButtonScheduler::Execute() {
- bool pressed = m_button->Grab();
-
- if (!m_pressedLast && pressed) {
- m_command->Cancel();
- }
-
- m_pressedLast = pressed;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
deleted file mode 100644
index 8fb1064107..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
+++ /dev/null
@@ -1,26 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/HeldButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-HeldButtonScheduler::HeldButtonScheduler(bool last, Trigger* button,
- Command* orders)
- : ButtonScheduler(last, button, orders) {}
-
-void HeldButtonScheduler::Execute() {
- bool pressed = m_button->Grab();
-
- if (pressed) {
- m_command->Start();
- } else if (m_pressedLast && !pressed) {
- m_command->Cancel();
- }
-
- m_pressedLast = pressed;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp
deleted file mode 100644
index 5adf83c999..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/InternalButton.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/InternalButton.h"
-
-using namespace frc;
-
-InternalButton::InternalButton(bool inverted)
- : m_pressed(inverted), m_inverted(inverted) {}
-
-void InternalButton::SetInverted(bool inverted) {
- m_inverted = inverted;
-}
-
-void InternalButton::SetPressed(bool pressed) {
- m_pressed = pressed;
-}
-
-bool InternalButton::Get() {
- return m_pressed ^ m_inverted;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp
deleted file mode 100644
index 459c076359..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/JoystickButton.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/JoystickButton.h"
-
-using namespace frc;
-
-JoystickButton::JoystickButton(GenericHID* joystick, int buttonNumber)
- : m_joystick(joystick), m_buttonNumber(buttonNumber) {}
-
-bool JoystickButton::Get() {
- return m_joystick->GetRawButton(m_buttonNumber);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp
deleted file mode 100644
index f5694a14f0..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/NetworkButton.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/NetworkButton.h"
-
-#include
-#include
-
-using namespace frc;
-
-NetworkButton::NetworkButton(std::string_view tableName, std::string_view field)
- : NetworkButton(nt::NetworkTableInstance::GetDefault().GetTable(tableName),
- field) {}
-
-NetworkButton::NetworkButton(std::shared_ptr table,
- std::string_view field)
- : m_entry(table->GetEntry(field)) {}
-
-bool NetworkButton::Get() {
- return m_entry.GetInstance().IsConnected() && m_entry.GetBoolean(false);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp
deleted file mode 100644
index 67b8caeedf..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/POVButton.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/POVButton.h"
-
-using namespace frc;
-
-POVButton::POVButton(GenericHID& joystick, int angle, int povNumber)
- : m_joystick(&joystick), m_angle(angle), m_povNumber(povNumber) {}
-
-bool POVButton::Get() {
- return m_joystick->GetPOV(m_povNumber) == m_angle;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
deleted file mode 100644
index 73705bc334..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/PressedButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-PressedButtonScheduler::PressedButtonScheduler(bool last, Trigger* button,
- Command* orders)
- : ButtonScheduler(last, button, orders) {}
-
-void PressedButtonScheduler::Execute() {
- bool pressed = m_button->Grab();
-
- if (!m_pressedLast && pressed) {
- m_command->Start();
- }
-
- m_pressedLast = pressed;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
deleted file mode 100644
index 647169b622..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ReleasedButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-ReleasedButtonScheduler::ReleasedButtonScheduler(bool last, Trigger* button,
- Command* orders)
- : ButtonScheduler(last, button, orders) {}
-
-void ReleasedButtonScheduler::Execute() {
- bool pressed = m_button->Grab();
-
- if (m_pressedLast && !pressed) {
- m_command->Start();
- }
-
- m_pressedLast = pressed;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
deleted file mode 100644
index d17b2e8315..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/buttons/ToggleButtonScheduler.h"
-
-#include "frc/buttons/Button.h"
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-ToggleButtonScheduler::ToggleButtonScheduler(bool last, Trigger* button,
- Command* orders)
- : ButtonScheduler(last, button, orders) {}
-
-void ToggleButtonScheduler::Execute() {
- bool pressed = m_button->Grab();
-
- if (!m_pressedLast && pressed) {
- if (m_command->IsRunning()) {
- m_command->Cancel();
- } else {
- m_command->Start();
- }
- }
-
- m_pressedLast = pressed;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp b/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp
deleted file mode 100644
index 9040df6c36..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/buttons/Trigger.cpp
+++ /dev/null
@@ -1,72 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include
-
-#include "frc/buttons/Button.h"
-#include "frc/buttons/CancelButtonScheduler.h"
-#include "frc/buttons/HeldButtonScheduler.h"
-#include "frc/buttons/PressedButtonScheduler.h"
-#include "frc/buttons/ReleasedButtonScheduler.h"
-#include "frc/buttons/ToggleButtonScheduler.h"
-
-using namespace frc;
-
-Trigger::Trigger(const Trigger& rhs) : SendableHelper(rhs) {}
-
-Trigger& Trigger::operator=(const Trigger& rhs) {
- SendableHelper::operator=(rhs);
- m_sendablePressed = false;
- return *this;
-}
-
-Trigger::Trigger(Trigger&& rhs)
- : SendableHelper(std::move(rhs)),
- m_sendablePressed(rhs.m_sendablePressed.load()) {
- rhs.m_sendablePressed = false;
-}
-
-Trigger& Trigger::operator=(Trigger&& rhs) {
- SendableHelper::operator=(std::move(rhs));
- m_sendablePressed = rhs.m_sendablePressed.load();
- rhs.m_sendablePressed = false;
- return *this;
-}
-
-bool Trigger::Grab() {
- return Get() || m_sendablePressed;
-}
-
-void Trigger::WhenActive(Command* command) {
- auto pbs = new PressedButtonScheduler(Grab(), this, command);
- pbs->Start();
-}
-
-void Trigger::WhileActive(Command* command) {
- auto hbs = new HeldButtonScheduler(Grab(), this, command);
- hbs->Start();
-}
-
-void Trigger::WhenInactive(Command* command) {
- auto rbs = new ReleasedButtonScheduler(Grab(), this, command);
- rbs->Start();
-}
-
-void Trigger::CancelWhenActive(Command* command) {
- auto cbs = new CancelButtonScheduler(Grab(), this, command);
- cbs->Start();
-}
-
-void Trigger::ToggleWhenActive(Command* command) {
- auto tbs = new ToggleButtonScheduler(Grab(), this, command);
- tbs->Start();
-}
-
-void Trigger::InitSendable(wpi::SendableBuilder& builder) {
- builder.SetSmartDashboardType("Button");
- builder.SetSafeState([=] { m_sendablePressed = false; });
- builder.AddBooleanProperty(
- "pressed", [=] { return Grab(); },
- [=](bool value) { m_sendablePressed = value; });
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp b/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp
deleted file mode 100644
index 778f9565de..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/Command.cpp
+++ /dev/null
@@ -1,315 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Command.h"
-
-#include
-
-#include
-#include
-
-#include "frc/Errors.h"
-#include "frc/RobotState.h"
-#include "frc/Timer.h"
-#include "frc/commands/CommandGroup.h"
-#include "frc/commands/Scheduler.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-int Command::m_commandCounter = 0;
-
-Command::Command() : Command("", -1_s) {}
-
-Command::Command(std::string_view name) : Command(name, -1_s) {}
-
-Command::Command(units::second_t timeout) : Command("", timeout) {}
-
-Command::Command(Subsystem& subsystem) : Command("", -1_s) {
- Requires(&subsystem);
-}
-
-Command::Command(std::string_view name, units::second_t timeout) {
- // We use -1.0 to indicate no timeout.
- if (timeout < 0_s && timeout != -1_s) {
- throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
- timeout.value());
- }
-
- m_timeout = timeout;
-
- // If name contains an empty string
- if (name.empty()) {
- wpi::SendableRegistry::Add(this,
- fmt::format("Command_{}", typeid(*this).name()));
- } else {
- wpi::SendableRegistry::Add(this, name);
- }
-}
-
-Command::Command(std::string_view name, Subsystem& subsystem)
- : Command(name, -1_s) {
- Requires(&subsystem);
-}
-
-Command::Command(units::second_t timeout, Subsystem& subsystem)
- : Command("", timeout) {
- Requires(&subsystem);
-}
-
-Command::Command(std::string_view name, units::second_t timeout,
- Subsystem& subsystem)
- : Command(name, timeout) {
- Requires(&subsystem);
-}
-
-units::second_t Command::TimeSinceInitialized() const {
- if (m_startTime < 0_s) {
- return 0_s;
- } else {
- return Timer::GetFPGATimestamp() - m_startTime;
- }
-}
-
-void Command::Requires(Subsystem* subsystem) {
- if (!AssertUnlocked("Can not add new requirement to command")) {
- return;
- }
-
- if (subsystem != nullptr) {
- m_requirements.insert(subsystem);
- } else {
- throw FRC_MakeError(err::NullParameter, "{}", "subsystem");
- }
-}
-
-void Command::Start() {
- LockChanges();
- if (m_parent != nullptr) {
- throw FRC_MakeError(
- err::CommandIllegalUse, "{}",
- "Can not start a command that is part of a command group");
- }
-
- m_completed = false;
- Scheduler::GetInstance()->AddCommand(this);
-}
-
-bool Command::Run() {
- if (!m_runWhenDisabled && m_parent == nullptr && RobotState::IsDisabled()) {
- Cancel();
- }
-
- if (IsCanceled()) {
- return false;
- }
-
- if (!m_initialized) {
- m_initialized = true;
- StartTiming();
- _Initialize();
- Initialize();
- }
- _Execute();
- Execute();
- return !IsFinished();
-}
-
-void Command::Cancel() {
- if (m_parent != nullptr) {
- throw FRC_MakeError(
- err::CommandIllegalUse, "{}",
- "Can not cancel a command that is part of a command group");
- }
-
- _Cancel();
-}
-
-bool Command::IsRunning() const {
- return m_running;
-}
-
-bool Command::IsInitialized() const {
- return m_initialized;
-}
-
-bool Command::IsCompleted() const {
- return m_completed;
-}
-
-bool Command::IsCanceled() const {
- return m_canceled;
-}
-
-bool Command::IsInterruptible() const {
- return m_interruptible;
-}
-
-void Command::SetInterruptible(bool interruptible) {
- m_interruptible = interruptible;
-}
-
-bool Command::DoesRequire(Subsystem* system) const {
- return m_requirements.count(system) > 0;
-}
-
-const Command::SubsystemSet& Command::GetRequirements() const {
- return m_requirements;
-}
-
-CommandGroup* Command::GetGroup() const {
- return m_parent;
-}
-
-void Command::SetRunWhenDisabled(bool run) {
- m_runWhenDisabled = run;
-}
-
-bool Command::WillRunWhenDisabled() const {
- return m_runWhenDisabled;
-}
-
-int Command::GetID() const {
- return m_commandID;
-}
-
-void Command::SetTimeout(units::second_t timeout) {
- if (timeout < 0_s) {
- throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
- timeout.value());
- } else {
- m_timeout = timeout;
- }
-}
-
-bool Command::IsTimedOut() const {
- return m_timeout != -1_s && TimeSinceInitialized() >= m_timeout;
-}
-
-bool Command::AssertUnlocked(std::string_view message) {
- if (m_locked) {
- throw FRC_MakeError(
- err::CommandIllegalUse,
- "{} after being started or being added to a command group", message);
- }
- return true;
-}
-
-void Command::SetParent(CommandGroup* parent) {
- if (parent == nullptr) {
- throw FRC_MakeError(err::NullParameter, "{}", "parent");
- } else if (m_parent != nullptr) {
- throw FRC_MakeError(err::CommandIllegalUse, "{}",
- "Can not give command to a command group after "
- "already being put in a command group");
- } else {
- LockChanges();
- m_parent = parent;
- }
-}
-
-bool Command::IsParented() const {
- return m_parent != nullptr;
-}
-
-void Command::ClearRequirements() {
- m_requirements.clear();
-}
-
-void Command::Initialize() {}
-
-void Command::Execute() {}
-
-void Command::End() {}
-
-void Command::Interrupted() {
- End();
-}
-
-void Command::_Initialize() {
- m_completed = false;
-}
-
-void Command::_Interrupted() {
- m_completed = true;
-}
-
-void Command::_Execute() {}
-
-void Command::_End() {
- m_completed = true;
-}
-
-void Command::_Cancel() {
- if (IsRunning()) {
- m_canceled = true;
- }
-}
-
-void Command::LockChanges() {
- m_locked = true;
-}
-
-void Command::Removed() {
- if (m_initialized) {
- if (IsCanceled()) {
- Interrupted();
- _Interrupted();
- } else {
- End();
- _End();
- }
- }
- m_initialized = false;
- m_canceled = false;
- m_running = false;
- m_completed = true;
-}
-
-void Command::StartRunning() {
- m_running = true;
- m_startTime = -1_s;
- m_completed = false;
-}
-
-void Command::StartTiming() {
- m_startTime = Timer::GetFPGATimestamp();
-}
-
-std::string Command::GetName() const {
- return wpi::SendableRegistry::GetName(this);
-}
-
-void Command::SetName(std::string_view name) {
- wpi::SendableRegistry::SetName(this, name);
-}
-
-std::string Command::GetSubsystem() const {
- return wpi::SendableRegistry::GetSubsystem(this);
-}
-
-void Command::SetSubsystem(std::string_view name) {
- wpi::SendableRegistry::SetSubsystem(this, name);
-}
-
-void Command::InitSendable(wpi::SendableBuilder& builder) {
- builder.SetSmartDashboardType("Command");
- builder.AddStringProperty(
- ".name", [=] { return wpi::SendableRegistry::GetName(this); }, nullptr);
- builder.AddBooleanProperty(
- "running", [=] { return IsRunning(); },
- [=](bool value) {
- if (value) {
- if (!IsRunning()) {
- Start();
- }
- } else {
- if (IsRunning()) {
- Cancel();
- }
- }
- });
- builder.AddBooleanProperty(
- ".isParented", [=] { return IsParented(); }, nullptr);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp b/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp
deleted file mode 100644
index 977795d93f..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/CommandGroup.cpp
+++ /dev/null
@@ -1,269 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/CommandGroup.h"
-
-#include "frc/Errors.h"
-
-using namespace frc;
-
-CommandGroup::CommandGroup(std::string_view name) : Command(name) {}
-
-void CommandGroup::AddSequential(Command* command) {
- if (!command) {
- throw FRC_MakeError(err::NullParameter, "{}", "command");
- }
- if (!AssertUnlocked("Cannot add new command to command group")) {
- return;
- }
-
- m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence);
-
- command->SetParent(this);
-
- // Iterate through command->GetRequirements() and call Requires() on each
- // required subsystem
- for (auto&& requirement : command->GetRequirements()) {
- Requires(requirement);
- }
-}
-
-void CommandGroup::AddSequential(Command* command, units::second_t timeout) {
- if (!command) {
- throw FRC_MakeError(err::NullParameter, "{}", "command");
- }
- if (!AssertUnlocked("Cannot add new command to command group")) {
- return;
- }
- if (timeout < 0_s) {
- throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
- timeout.value());
- }
-
- m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence,
- timeout);
-
- command->SetParent(this);
-
- // Iterate through command->GetRequirements() and call Requires() on each
- // required subsystem
- for (auto&& requirement : command->GetRequirements()) {
- Requires(requirement);
- }
-}
-
-void CommandGroup::AddParallel(Command* command) {
- if (!command) {
- throw FRC_MakeError(err::NullParameter, "{}", "command");
- return;
- }
- if (!AssertUnlocked("Cannot add new command to command group")) {
- return;
- }
-
- m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild);
-
- command->SetParent(this);
-
- // Iterate through command->GetRequirements() and call Requires() on each
- // required subsystem
- for (auto&& requirement : command->GetRequirements()) {
- Requires(requirement);
- }
-}
-
-void CommandGroup::AddParallel(Command* command, units::second_t timeout) {
- if (!command) {
- throw FRC_MakeError(err::NullParameter, "{}", "command");
- }
- if (!AssertUnlocked("Cannot add new command to command group")) {
- return;
- }
- if (timeout < 0_s) {
- throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
- timeout.value());
- }
-
- m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild,
- timeout);
-
- command->SetParent(this);
-
- // Iterate through command->GetRequirements() and call Requires() on each
- // required subsystem
- for (auto&& requirement : command->GetRequirements()) {
- Requires(requirement);
- }
-}
-
-bool CommandGroup::IsInterruptible() const {
- if (!Command::IsInterruptible()) {
- return false;
- }
-
- if (m_currentCommandIndex != -1 &&
- static_cast(m_currentCommandIndex) < m_commands.size()) {
- Command* cmd = m_commands[m_currentCommandIndex].m_command;
- if (!cmd->IsInterruptible()) {
- return false;
- }
- }
-
- for (const auto& child : m_children) {
- if (!child->m_command->IsInterruptible()) {
- return false;
- }
- }
-
- return true;
-}
-
-int CommandGroup::GetSize() const {
- return m_children.size();
-}
-
-void CommandGroup::Initialize() {}
-
-void CommandGroup::Execute() {}
-
-bool CommandGroup::IsFinished() {
- return static_cast(m_currentCommandIndex) >= m_commands.size() &&
- m_children.empty();
-}
-
-void CommandGroup::End() {}
-
-void CommandGroup::Interrupted() {}
-
-void CommandGroup::_Initialize() {
- m_currentCommandIndex = -1;
-}
-
-void CommandGroup::_Execute() {
- CommandGroupEntry* entry;
- Command* cmd = nullptr;
- bool firstRun = false;
-
- if (m_currentCommandIndex == -1) {
- firstRun = true;
- m_currentCommandIndex = 0;
- }
-
- // While there are still commands in this group to run
- while (static_cast(m_currentCommandIndex) < m_commands.size()) {
- // If a command is prepared to run
- if (cmd != nullptr) {
- // If command timed out, cancel it so it's removed from the Scheduler
- if (entry->IsTimedOut()) {
- cmd->_Cancel();
- }
-
- // If command finished or was canceled, remove it from Scheduler
- if (cmd->Run()) {
- break;
- } else {
- cmd->Removed();
-
- // Advance to next command in group
- m_currentCommandIndex++;
- firstRun = true;
- cmd = nullptr;
- continue;
- }
- }
-
- entry = &m_commands[m_currentCommandIndex];
- cmd = nullptr;
-
- switch (entry->m_state) {
- case CommandGroupEntry::kSequence_InSequence:
- cmd = entry->m_command;
- if (firstRun) {
- cmd->StartRunning();
- CancelConflicts(cmd);
- firstRun = false;
- }
- break;
-
- case CommandGroupEntry::kSequence_BranchPeer:
- // Start executing a parallel command and advance to next entry in group
- m_currentCommandIndex++;
- entry->m_command->Start();
- break;
-
- case CommandGroupEntry::kSequence_BranchChild:
- m_currentCommandIndex++;
-
- /* Causes scheduler to skip children of current command which require
- * the same subsystems as it
- */
- CancelConflicts(entry->m_command);
- entry->m_command->StartRunning();
-
- // Add current command entry to list of children of this group
- m_children.push_back(entry);
- break;
- }
- }
-
- // Run Children
- for (auto& entry : m_children) {
- auto child = entry->m_command;
- if (entry->IsTimedOut()) {
- child->_Cancel();
- }
-
- // If child finished or was canceled, set it to nullptr. nullptr entries
- // are removed later.
- if (!child->Run()) {
- child->Removed();
- entry = nullptr;
- }
- }
-
- m_children.erase(std::remove(m_children.begin(), m_children.end(), nullptr),
- m_children.end());
-}
-
-void CommandGroup::_End() {
- // Theoretically, we don't have to check this, but we do if teams override the
- // IsFinished method
- if (m_currentCommandIndex != -1 &&
- static_cast(m_currentCommandIndex) < m_commands.size()) {
- Command* cmd = m_commands[m_currentCommandIndex].m_command;
- cmd->_Cancel();
- cmd->Removed();
- }
-
- for (auto& child : m_children) {
- Command* cmd = child->m_command;
- cmd->_Cancel();
- cmd->Removed();
- }
- m_children.clear();
-}
-
-void CommandGroup::_Interrupted() {
- _End();
-}
-
-void CommandGroup::CancelConflicts(Command* command) {
- for (auto childIter = m_children.begin(); childIter != m_children.end();) {
- Command* child = (*childIter)->m_command;
- bool erased = false;
-
- for (auto&& requirement : command->GetRequirements()) {
- if (child->DoesRequire(requirement)) {
- child->_Cancel();
- child->Removed();
- childIter = m_children.erase(childIter);
- erased = true;
- break;
- }
- }
- if (!erased) {
- childIter++;
- }
- }
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp b/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp
deleted file mode 100644
index 1e6f8c7ac0..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/CommandGroupEntry.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/CommandGroupEntry.h"
-
-#include "frc/commands/Command.h"
-
-using namespace frc;
-
-CommandGroupEntry::CommandGroupEntry(Command* command, Sequence state,
- units::second_t timeout)
- : m_timeout(timeout), m_command(command), m_state(state) {}
-
-bool CommandGroupEntry::IsTimedOut() const {
- if (m_timeout < 0_s) {
- return false;
- }
- auto time = m_command->TimeSinceInitialized();
- if (time == 0_s) {
- return false;
- }
- return time >= m_timeout;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp
deleted file mode 100644
index e2867b5c8e..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/ConditionalCommand.cpp
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/ConditionalCommand.h"
-
-#include "frc/commands/Scheduler.h"
-
-using namespace frc;
-
-static void RequireAll(Command& command, Command* onTrue, Command* onFalse) {
- if (onTrue != nullptr) {
- for (auto requirement : onTrue->GetRequirements()) {
- command.Requires(requirement);
- }
- }
- if (onFalse != nullptr) {
- for (auto requirement : onFalse->GetRequirements()) {
- command.Requires(requirement);
- }
- }
-}
-
-ConditionalCommand::ConditionalCommand(Command* onTrue, Command* onFalse) {
- m_onTrue = onTrue;
- m_onFalse = onFalse;
-
- RequireAll(*this, onTrue, onFalse);
-}
-
-ConditionalCommand::ConditionalCommand(std::string_view name, Command* onTrue,
- Command* onFalse)
- : Command(name) {
- m_onTrue = onTrue;
- m_onFalse = onFalse;
-
- RequireAll(*this, onTrue, onFalse);
-}
-
-void ConditionalCommand::_Initialize() {
- if (Condition()) {
- m_chosenCommand = m_onTrue;
- } else {
- m_chosenCommand = m_onFalse;
- }
-
- if (m_chosenCommand != nullptr) {
- // This is a hack to make canceling the chosen command inside a
- // CommandGroup work properly
- m_chosenCommand->ClearRequirements();
-
- m_chosenCommand->Start();
- }
- Command::_Initialize();
-}
-
-void ConditionalCommand::_Cancel() {
- if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
- m_chosenCommand->Cancel();
- }
-
- Command::_Cancel();
-}
-
-bool ConditionalCommand::IsFinished() {
- if (m_chosenCommand != nullptr) {
- return m_chosenCommand->IsCompleted();
- } else {
- return true;
- }
-}
-
-void ConditionalCommand::_Interrupted() {
- if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
- m_chosenCommand->Cancel();
- }
-
- Command::_Interrupted();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp
deleted file mode 100644
index d8f3309cc0..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/InstantCommand.cpp
+++ /dev/null
@@ -1,47 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/InstantCommand.h"
-
-#include
-
-using namespace frc;
-
-InstantCommand::InstantCommand(std::string_view name) : Command(name) {}
-
-InstantCommand::InstantCommand(Subsystem& subsystem) : Command(subsystem) {}
-
-InstantCommand::InstantCommand(std::string_view name, Subsystem& subsystem)
- : Command(name, subsystem) {}
-
-InstantCommand::InstantCommand(std::function func)
- : m_func(std::move(func)) {}
-
-InstantCommand::InstantCommand(Subsystem& subsystem, std::function func)
- : InstantCommand(subsystem) {
- m_func = func;
-}
-
-InstantCommand::InstantCommand(std::string_view name,
- std::function func)
- : InstantCommand(name) {
- m_func = func;
-}
-
-InstantCommand::InstantCommand(std::string_view name, Subsystem& subsystem,
- std::function func)
- : InstantCommand(name, subsystem) {
- m_func = func;
-}
-
-void InstantCommand::_Initialize() {
- Command::_Initialize();
- if (m_func) {
- m_func();
- }
-}
-
-bool InstantCommand::IsFinished() {
- return true;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp
deleted file mode 100644
index e71556afee..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/PIDCommand.cpp
+++ /dev/null
@@ -1,119 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PIDCommand.h"
-
-#include
-
-using namespace frc;
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
- double f, double period)
- : Command(name) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double f, double period) {
- m_controller =
- std::make_shared(p, i, d, f, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d)
- : Command(name) {
- m_controller = std::make_shared(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
- double period)
- : Command(name) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d) {
- m_controller = std::make_shared(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double period) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
- double f, double period, Subsystem& subsystem)
- : Command(name, subsystem) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double f, double period,
- Subsystem& subsystem)
- : Command(subsystem) {
- m_controller =
- std::make_shared(p, i, d, f, this, this, period);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
- Subsystem& subsystem)
- : Command(name, subsystem) {
- m_controller = std::make_shared(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(std::string_view name, double p, double i, double d,
- double period, Subsystem& subsystem)
- : Command(name, subsystem) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, Subsystem& subsystem) {
- m_controller = std::make_shared(p, i, d, this, this);
-}
-
-PIDCommand::PIDCommand(double p, double i, double d, double period,
- Subsystem& subsystem) {
- m_controller = std::make_shared(p, i, d, this, this, period);
-}
-
-void PIDCommand::_Initialize() {
- m_controller->Enable();
-}
-
-void PIDCommand::_End() {
- m_controller->Disable();
-}
-
-void PIDCommand::_Interrupted() {
- _End();
-}
-
-void PIDCommand::SetSetpointRelative(double deltaSetpoint) {
- SetSetpoint(GetSetpoint() + deltaSetpoint);
-}
-
-void PIDCommand::PIDWrite(double output) {
- UsePIDOutput(output);
-}
-
-double PIDCommand::PIDGet() {
- return ReturnPIDInput();
-}
-
-std::shared_ptr PIDCommand::GetPIDController() const {
- return m_controller;
-}
-
-void PIDCommand::SetSetpoint(double setpoint) {
- m_controller->SetSetpoint(setpoint);
-}
-
-double PIDCommand::GetSetpoint() const {
- return m_controller->GetSetpoint();
-}
-
-double PIDCommand::GetPosition() {
- return ReturnPIDInput();
-}
-
-void PIDCommand::InitSendable(wpi::SendableBuilder& builder) {
- m_controller->InitSendable(builder);
- Command::InitSendable(builder);
- builder.SetSmartDashboardType("PIDCommand");
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp b/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp
deleted file mode 100644
index f76288b46c..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/PIDSubsystem.cpp
+++ /dev/null
@@ -1,110 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PIDSubsystem.h"
-
-#include "frc/PIDController.h"
-
-using namespace frc;
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d)
- : Subsystem(name) {
- m_controller = std::make_shared(p, i, d, this, this);
- AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d,
- double f)
- : Subsystem(name) {
- m_controller = std::make_shared(p, i, d, f, this, this);
- AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(std::string_view name, double p, double i, double d,
- double f, double period)
- : Subsystem(name) {
- m_controller =
- std::make_shared(p, i, d, f, this, this, period);
- AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d)
- : Subsystem("PIDSubsystem") {
- m_controller = std::make_shared(p, i, d, this, this);
- AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d, double f)
- : Subsystem("PIDSubsystem") {
- m_controller = std::make_shared(p, i, d, f, this, this);
- AddChild("PIDController", m_controller);
-}
-
-PIDSubsystem::PIDSubsystem(double p, double i, double d, double f,
- double period)
- : Subsystem("PIDSubsystem") {
- m_controller =
- std::make_shared(p, i, d, f, this, this, period);
- AddChild("PIDController", m_controller);
-}
-
-void PIDSubsystem::Enable() {
- m_controller->Enable();
-}
-
-void PIDSubsystem::Disable() {
- m_controller->Disable();
-}
-
-void PIDSubsystem::PIDWrite(double output) {
- UsePIDOutput(output);
-}
-
-double PIDSubsystem::PIDGet() {
- return ReturnPIDInput();
-}
-
-void PIDSubsystem::SetSetpoint(double setpoint) {
- m_controller->SetSetpoint(setpoint);
-}
-
-void PIDSubsystem::SetSetpointRelative(double deltaSetpoint) {
- SetSetpoint(GetSetpoint() + deltaSetpoint);
-}
-
-void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) {
- m_controller->SetInputRange(minimumInput, maximumInput);
-}
-
-void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) {
- m_controller->SetOutputRange(minimumOutput, maximumOutput);
-}
-
-double PIDSubsystem::GetSetpoint() {
- return m_controller->GetSetpoint();
-}
-
-double PIDSubsystem::GetPosition() {
- return ReturnPIDInput();
-}
-
-double PIDSubsystem::GetRate() {
- return ReturnPIDInput();
-}
-
-void PIDSubsystem::SetAbsoluteTolerance(double absValue) {
- m_controller->SetAbsoluteTolerance(absValue);
-}
-
-void PIDSubsystem::SetPercentTolerance(double percent) {
- m_controller->SetPercentTolerance(percent);
-}
-
-bool PIDSubsystem::OnTarget() const {
- return m_controller->OnTarget();
-}
-
-std::shared_ptr PIDSubsystem::GetPIDController() {
- return m_controller;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp
deleted file mode 100644
index ca8f49a84a..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/PrintCommand.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/PrintCommand.h"
-
-#include
-
-using namespace frc;
-
-PrintCommand::PrintCommand(std::string_view message)
- : InstantCommand(fmt::format("Print \"{}\"", message)) {
- m_message = message;
-}
-
-void PrintCommand::Initialize() {
- fmt::print("{}\n", m_message);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp b/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp
deleted file mode 100644
index 701162c6f0..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/Scheduler.cpp
+++ /dev/null
@@ -1,262 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Scheduler.h"
-
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-#include
-
-#include "frc/Errors.h"
-#include "frc/buttons/ButtonScheduler.h"
-#include "frc/commands/Command.h"
-#include "frc/commands/Subsystem.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-struct Scheduler::Impl {
- void Remove(Command* command);
- void ProcessCommandAddition(Command* command);
-
- using SubsystemSet = std::set;
- SubsystemSet subsystems;
- wpi::mutex buttonsMutex;
- using ButtonVector = std::vector>;
- ButtonVector buttons;
- using CommandVector = std::vector;
- wpi::mutex additionsMutex;
- CommandVector additions;
- using CommandSet = std::set;
- CommandSet commands;
- bool adding = false;
- bool enabled = true;
- std::vector commandsBuf;
- std::vector idsBuf;
- bool runningCommandsChanged = false;
-};
-
-Scheduler* Scheduler::GetInstance() {
- static Scheduler instance;
- return &instance;
-}
-
-void Scheduler::AddCommand(Command* command) {
- std::scoped_lock lock(m_impl->additionsMutex);
- if (std::find(m_impl->additions.begin(), m_impl->additions.end(), command) !=
- m_impl->additions.end()) {
- return;
- }
- m_impl->additions.push_back(command);
-}
-
-void Scheduler::AddButton(ButtonScheduler* button) {
- std::scoped_lock lock(m_impl->buttonsMutex);
- m_impl->buttons.emplace_back(button);
-}
-
-void Scheduler::RegisterSubsystem(Subsystem* subsystem) {
- if (!subsystem) {
- throw FRC_MakeError(err::NullParameter, "{}", "subsystem");
- }
- m_impl->subsystems.insert(subsystem);
-}
-
-void Scheduler::Run() {
- // Get button input (going backwards preserves button priority)
- {
- if (!m_impl->enabled) {
- return;
- }
-
- std::scoped_lock lock(m_impl->buttonsMutex);
- for (auto& button : m_impl->buttons) {
- button->Execute();
- }
- }
-
- // Call every subsystem's periodic method
- for (auto& subsystem : m_impl->subsystems) {
- subsystem->Periodic();
- }
-
- m_impl->runningCommandsChanged = false;
-
- // Loop through the commands
- for (auto cmdIter = m_impl->commands.begin();
- cmdIter != m_impl->commands.end();) {
- Command* command = *cmdIter;
- // Increment before potentially removing to keep the iterator valid
- ++cmdIter;
- if (!command->Run()) {
- Remove(command);
- m_impl->runningCommandsChanged = true;
- }
- }
-
- // Add the new things
- {
- std::scoped_lock lock(m_impl->additionsMutex);
- for (auto& addition : m_impl->additions) {
- // Check to make sure no adding during adding
- if (m_impl->adding) {
- FRC_ReportError(warn::IncompatibleState, "{}",
- "Can not start command from cancel method");
- } else {
- m_impl->ProcessCommandAddition(addition);
- }
- }
- m_impl->additions.clear();
- }
-
- // Add in the defaults
- for (auto& subsystem : m_impl->subsystems) {
- if (subsystem->GetCurrentCommand() == nullptr) {
- if (m_impl->adding) {
- FRC_ReportError(warn::IncompatibleState, "{}",
- "Can not start command from cancel method");
- } else {
- m_impl->ProcessCommandAddition(subsystem->GetDefaultCommand());
- }
- }
- subsystem->ConfirmCommand();
- }
-}
-
-void Scheduler::Remove(Command* command) {
- if (!command) {
- throw FRC_MakeError(err::NullParameter, "{}", "command");
- }
-
- m_impl->Remove(command);
-}
-
-void Scheduler::RemoveAll() {
- while (m_impl->commands.size() > 0) {
- Remove(*m_impl->commands.begin());
- }
-}
-
-void Scheduler::ResetAll() {
- RemoveAll();
- m_impl->subsystems.clear();
- m_impl->buttons.clear();
- m_impl->additions.clear();
- m_impl->commands.clear();
-}
-
-void Scheduler::SetEnabled(bool enabled) {
- m_impl->enabled = enabled;
-}
-
-void Scheduler::InitSendable(nt::NTSendableBuilder& builder) {
- builder.SetSmartDashboardType("Scheduler");
- auto namesEntry = builder.GetEntry("Names");
- auto idsEntry = builder.GetEntry("Ids");
- auto cancelEntry = builder.GetEntry("Cancel");
- builder.SetUpdateTable([=] {
- // Get the list of possible commands to cancel
- auto new_toCancel = cancelEntry.GetValue();
- wpi::span toCancel;
- if (new_toCancel) {
- toCancel = new_toCancel->GetDoubleArray();
- }
-
- // Cancel commands whose cancel buttons were pressed on the SmartDashboard
- if (!toCancel.empty()) {
- for (auto& command : m_impl->commands) {
- for (const auto& canceled : toCancel) {
- if (command->GetID() == canceled) {
- command->Cancel();
- }
- }
- }
- nt::NetworkTableEntry(cancelEntry).SetDoubleArray({});
- }
-
- // Set the running commands
- if (m_impl->runningCommandsChanged) {
- m_impl->commandsBuf.resize(0);
- m_impl->idsBuf.resize(0);
- for (const auto& command : m_impl->commands) {
- m_impl->commandsBuf.emplace_back(
- wpi::SendableRegistry::GetName(command));
- m_impl->idsBuf.emplace_back(command->GetID());
- }
- nt::NetworkTableEntry(namesEntry).SetStringArray(m_impl->commandsBuf);
- nt::NetworkTableEntry(idsEntry).SetDoubleArray(m_impl->idsBuf);
- }
- });
-}
-
-Scheduler::Scheduler() : m_impl(new Impl) {
- HAL_Report(HALUsageReporting::kResourceType_Command,
- HALUsageReporting::kCommand_Scheduler);
- wpi::SendableRegistry::AddLW(this, "Scheduler");
- frc::LiveWindow::SetEnabledCallback([this] {
- this->SetEnabled(false);
- this->RemoveAll();
- });
- frc::LiveWindow::SetDisabledCallback([this] { this->SetEnabled(true); });
-}
-
-Scheduler::~Scheduler() {
- wpi::SendableRegistry::Remove(this);
- frc::LiveWindow::SetEnabledCallback(nullptr);
- frc::LiveWindow::SetDisabledCallback(nullptr);
-}
-
-void Scheduler::Impl::Remove(Command* command) {
- if (!commands.erase(command)) {
- return;
- }
-
- for (auto&& requirement : command->GetRequirements()) {
- requirement->SetCurrentCommand(nullptr);
- }
-
- command->Removed();
-}
-
-void Scheduler::Impl::ProcessCommandAddition(Command* command) {
- if (command == nullptr) {
- return;
- }
-
- // Only add if not already in
- auto found = commands.find(command);
- if (found == commands.end()) {
- // Check that the requirements can be had
- const auto& requirements = command->GetRequirements();
- for (const auto requirement : requirements) {
- if (requirement->GetCurrentCommand() != nullptr &&
- !requirement->GetCurrentCommand()->IsInterruptible()) {
- return;
- }
- }
-
- // Give it the requirements
- adding = true;
- for (auto&& requirement : requirements) {
- if (requirement->GetCurrentCommand() != nullptr) {
- requirement->GetCurrentCommand()->Cancel();
- Remove(requirement->GetCurrentCommand());
- }
- requirement->SetCurrentCommand(command);
- }
- adding = false;
-
- commands.insert(command);
-
- command->StartRunning();
- runningCommandsChanged = true;
- }
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp
deleted file mode 100644
index 05dc0793ba..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/StartCommand.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/StartCommand.h"
-
-using namespace frc;
-
-StartCommand::StartCommand(Command* commandToStart)
- : InstantCommand("StartCommand") {
- m_commandToFork = commandToStart;
-}
-
-void StartCommand::Initialize() {
- m_commandToFork->Start();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp b/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp
deleted file mode 100644
index 824872f0c4..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/Subsystem.cpp
+++ /dev/null
@@ -1,137 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/Subsystem.h"
-
-#include
-#include
-
-#include "frc/Errors.h"
-#include "frc/commands/Command.h"
-#include "frc/commands/Scheduler.h"
-#include "frc/livewindow/LiveWindow.h"
-
-using namespace frc;
-
-Subsystem::Subsystem(std::string_view name) {
- wpi::SendableRegistry::AddLW(this, name, name);
- Scheduler::GetInstance()->RegisterSubsystem(this);
-}
-
-void Subsystem::SetDefaultCommand(Command* command) {
- if (command == nullptr) {
- m_defaultCommand = nullptr;
- } else {
- const auto& reqs = command->GetRequirements();
- if (std::find(reqs.begin(), reqs.end(), this) == reqs.end()) {
- throw FRC_MakeError(err::CommandIllegalUse, "{}",
- "A default command must require the subsystem");
- }
-
- m_defaultCommand = command;
- }
-}
-
-Command* Subsystem::GetDefaultCommand() {
- if (!m_initializedDefaultCommand) {
- m_initializedDefaultCommand = true;
- InitDefaultCommand();
- }
- return m_defaultCommand;
-}
-
-std::string Subsystem::GetDefaultCommandName() {
- Command* defaultCommand = GetDefaultCommand();
- if (defaultCommand) {
- return wpi::SendableRegistry::GetName(defaultCommand);
- } else {
- return {};
- }
-}
-
-void Subsystem::SetCurrentCommand(Command* command) {
- m_currentCommand = command;
- m_currentCommandChanged = true;
-}
-
-Command* Subsystem::GetCurrentCommand() const {
- return m_currentCommand;
-}
-
-std::string Subsystem::GetCurrentCommandName() const {
- Command* currentCommand = GetCurrentCommand();
- if (currentCommand) {
- return wpi::SendableRegistry::GetName(currentCommand);
- } else {
- return {};
- }
-}
-
-void Subsystem::Periodic() {}
-
-void Subsystem::InitDefaultCommand() {}
-
-std::string Subsystem::GetName() const {
- return wpi::SendableRegistry::GetName(this);
-}
-
-void Subsystem::SetName(std::string_view name) {
- wpi::SendableRegistry::SetName(this, name);
-}
-
-std::string Subsystem::GetSubsystem() const {
- return wpi::SendableRegistry::GetSubsystem(this);
-}
-
-void Subsystem::SetSubsystem(std::string_view name) {
- wpi::SendableRegistry::SetSubsystem(this, name);
-}
-
-void Subsystem::AddChild(std::string_view name,
- std::shared_ptr child) {
- AddChild(name, *child);
-}
-
-void Subsystem::AddChild(std::string_view name, wpi::Sendable* child) {
- AddChild(name, *child);
-}
-
-void Subsystem::AddChild(std::string_view name, wpi::Sendable& child) {
- wpi::SendableRegistry::AddLW(&child,
- wpi::SendableRegistry::GetSubsystem(this), name);
-}
-
-void Subsystem::AddChild(std::shared_ptr child) {
- AddChild(*child);
-}
-
-void Subsystem::AddChild(wpi::Sendable* child) {
- AddChild(*child);
-}
-
-void Subsystem::AddChild(wpi::Sendable& child) {
- wpi::SendableRegistry::SetSubsystem(
- &child, wpi::SendableRegistry::GetSubsystem(this));
- wpi::SendableRegistry::EnableLiveWindow(&child);
-}
-
-void Subsystem::ConfirmCommand() {
- if (m_currentCommandChanged) {
- m_currentCommandChanged = false;
- }
-}
-
-void Subsystem::InitSendable(wpi::SendableBuilder& builder) {
- builder.SetSmartDashboardType("Subsystem");
-
- builder.AddBooleanProperty(
- ".hasDefault", [=] { return m_defaultCommand != nullptr; }, nullptr);
- builder.AddStringProperty(
- ".default", [=] { return GetDefaultCommandName(); }, nullptr);
-
- builder.AddBooleanProperty(
- ".hasCommand", [=] { return m_currentCommand != nullptr; }, nullptr);
- builder.AddStringProperty(
- ".command", [=] { return GetCurrentCommandName(); }, nullptr);
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp
deleted file mode 100644
index 5c2ccd48bc..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/TimedCommand.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/TimedCommand.h"
-
-using namespace frc;
-
-TimedCommand::TimedCommand(std::string_view name, units::second_t timeout)
- : Command(name, timeout) {}
-
-TimedCommand::TimedCommand(units::second_t timeout) : Command(timeout) {}
-
-TimedCommand::TimedCommand(std::string_view name, units::second_t timeout,
- Subsystem& subsystem)
- : Command(name, timeout, subsystem) {}
-
-TimedCommand::TimedCommand(units::second_t timeout, Subsystem& subsystem)
- : Command(timeout, subsystem) {}
-
-bool TimedCommand::IsFinished() {
- return IsTimedOut();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp
deleted file mode 100644
index b4d44e05ae..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/WaitCommand.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitCommand.h"
-
-#include
-
-using namespace frc;
-
-WaitCommand::WaitCommand(units::second_t timeout)
- : TimedCommand(fmt::format("Wait({})", timeout.value()), timeout) {}
-
-WaitCommand::WaitCommand(std::string_view name, units::second_t timeout)
- : TimedCommand(name, timeout) {}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp b/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp
deleted file mode 100644
index e02a63063c..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/WaitForChildren.cpp
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitForChildren.h"
-
-#include "frc/commands/CommandGroup.h"
-
-using namespace frc;
-
-WaitForChildren::WaitForChildren(units::second_t timeout)
- : Command("WaitForChildren", timeout) {}
-
-WaitForChildren::WaitForChildren(std::string_view name, units::second_t timeout)
- : Command(name, timeout) {}
-
-bool WaitForChildren::IsFinished() {
- return GetGroup() == nullptr || GetGroup()->GetSize() == 0;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp b/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp
deleted file mode 100644
index bb127b1929..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/commands/WaitUntilCommand.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/commands/WaitUntilCommand.h"
-
-#include "frc/Timer.h"
-
-using namespace frc;
-
-WaitUntilCommand::WaitUntilCommand(units::second_t time)
- : Command("WaitUntilCommand", time) {
- m_time = time;
-}
-
-WaitUntilCommand::WaitUntilCommand(std::string_view name, units::second_t time)
- : Command(name, time) {
- m_time = time;
-}
-
-bool WaitUntilCommand::IsFinished() {
- return Timer::GetMatchTime() >= m_time;
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp
deleted file mode 100644
index 62801e75d6..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogAccelerometer.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDAnalogAccelerometer.h"
-
-using namespace frc;
-
-double PIDAnalogAccelerometer::PIDGet() {
- return GetAcceleration();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp
deleted file mode 100644
index d6a9ace5d1..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogGyro.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDAnalogGyro.h"
-
-using namespace frc;
-
-double PIDAnalogGyro::PIDGet() {
- switch (GetPIDSourceType()) {
- case PIDSourceType::kRate:
- return GetRate();
- case PIDSourceType::kDisplacement:
- return GetAngle();
- default:
- return 0;
- }
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp
deleted file mode 100644
index d8dc7165aa..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogInput.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDAnalogInput.h"
-
-using namespace frc;
-
-double PIDAnalogInput::PIDGet() {
- return GetAverageVoltage();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp
deleted file mode 100644
index 7b44f6b177..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDAnalogPotentiometer.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDAnalogPotentiometer.h"
-
-using namespace frc;
-
-double PIDAnalogPotentiometer::PIDGet() {
- return Get();
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp
deleted file mode 100644
index b98d1c9753..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDEncoder.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDEncoder.h"
-
-using namespace frc;
-
-double PIDEncoder::PIDGet() {
- switch (GetPIDSourceType()) {
- case PIDSourceType::kDisplacement:
- return GetDistance();
- case PIDSourceType::kRate:
- return GetRate();
- default:
- return 0.0;
- }
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp
deleted file mode 100644
index 68d0be301f..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDMotorController.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDMotorController.h"
-
-#include
-#include
-#include
-
-using namespace frc;
-
-PIDMotorController::PIDMotorController(MotorController& motorController)
- : m_motorController(motorController) {}
-
-void PIDMotorController::Set(double speed) {
- m_motorController.Set(m_isInverted ? -speed : speed);
-}
-
-double PIDMotorController::Get() const {
- return m_motorController.Get() * (m_isInverted ? -1.0 : 1.0);
-}
-
-void PIDMotorController::SetInverted(bool isInverted) {
- m_isInverted = isInverted;
-}
-
-bool PIDMotorController::GetInverted() const {
- return m_isInverted;
-}
-
-void PIDMotorController::Disable() {
- m_motorController.Disable();
-}
-
-void PIDMotorController::StopMotor() {
- Disable();
-}
-
-void PIDMotorController::PIDWrite(double output) {
- m_motorController.Set(output);
-}
-
-void PIDMotorController::InitSendable(wpi::SendableBuilder& builder) {
- builder.SetSmartDashboardType("Motor Controller");
- builder.SetActuator(true);
- builder.SetSafeState([=] { Disable(); });
- builder.AddDoubleProperty(
- "Value", [=] { return Get(); }, [=](double value) { Set(value); });
-}
diff --git a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp b/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp
deleted file mode 100644
index 4c02f17c6a..0000000000
--- a/wpilibOldCommands/src/main/native/cpp/pidwrappers/PIDUltrasonic.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "frc/pidwrappers/PIDUltrasonic.h"
-
-using namespace frc;
-
-double PIDUltrasonic::PIDGet() {
- return GetRange().value();
-}
diff --git a/wpilibOldCommands/src/main/native/include/frc/PIDBase.h b/wpilibOldCommands/src/main/native/include/frc/PIDBase.h
deleted file mode 100644
index 8c72ae77dc..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/PIDBase.h
+++ /dev/null
@@ -1,407 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-#include "frc/PIDInterface.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/Timer.h"
-#include "frc/filter/LinearFilter.h"
-
-namespace frc {
-
-/**
- * Class implements a PID Control Loop.
- *
- * Creates a separate thread which reads the given PIDSource and takes care of
- * the integral calculations, as well as writing the given PIDOutput.
- *
- * This feedback controller runs in discrete time, so time deltas are not used
- * in the integral and derivative calculations. Therefore, the sample rate
- * affects the controller's behavior for a given set of PID constants.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-class PIDBase : public PIDInterface,
- public PIDOutput,
- public wpi::Sendable,
- public wpi::SendableHelper {
- public:
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- */
- WPI_DEPRECATED("All APIs which use this have been deprecated.")
- PIDBase(double p, double i, double d, PIDSource& source, PIDOutput& output);
-
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param f the feedforward coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- */
- WPI_DEPRECATED("All APIs which use this have been deprecated.")
- PIDBase(double p, double i, double d, double f, PIDSource& source,
- PIDOutput& output);
-
- ~PIDBase() override = default;
-
- /**
- * Return the current PID result.
- *
- * This is always centered on zero and constrained the the max and min outs.
- *
- * @return the latest calculated output
- */
- virtual double Get() const;
-
- /**
- * Set the PID controller to consider the input to be continuous,
- *
- * Rather then using the max and min input range as constraints, it considers
- * them to be the same point and automatically calculates the shortest route
- * to the setpoint.
- *
- * @param continuous true turns on continuous, false turns off continuous
- */
- virtual void SetContinuous(bool continuous = true);
-
- /**
- * Sets the maximum and minimum values expected from the input.
- *
- * @param minimumInput the minimum value expected from the input
- * @param maximumInput the maximum value expected from the output
- */
- virtual void SetInputRange(double minimumInput, double maximumInput);
-
- /**
- * Sets the minimum and maximum values to write.
- *
- * @param minimumOutput the minimum value to write to the output
- * @param maximumOutput the maximum value to write to the output
- */
- virtual void SetOutputRange(double minimumOutput, double maximumOutput);
-
- /**
- * Set the PID Controller gain parameters.
- *
- * Set the proportional, integral, and differential coefficients.
- *
- * @param p Proportional coefficient
- * @param i Integral coefficient
- * @param d Differential coefficient
- */
- void SetPID(double p, double i, double d) override;
-
- /**
- * Set the PID Controller gain parameters.
- *
- * Set the proportional, integral, and differential coefficients.
- *
- * @param p Proportional coefficient
- * @param i Integral coefficient
- * @param d Differential coefficient
- * @param f Feed forward coefficient
- */
- virtual void SetPID(double p, double i, double d, double f);
-
- /**
- * Set the Proportional coefficient of the PID controller gain.
- *
- * @param p proportional coefficient
- */
- void SetP(double p);
-
- /**
- * Set the Integral coefficient of the PID controller gain.
- *
- * @param i integral coefficient
- */
- void SetI(double i);
-
- /**
- * Set the Differential coefficient of the PID controller gain.
- *
- * @param d differential coefficient
- */
- void SetD(double d);
-
- /**
- * Get the Feed forward coefficient of the PID controller gain.
- *
- * @param f Feed forward coefficient
- */
- void SetF(double f);
-
- /**
- * Get the Proportional coefficient.
- *
- * @return proportional coefficient
- */
- double GetP() const override;
-
- /**
- * Get the Integral coefficient.
- *
- * @return integral coefficient
- */
- double GetI() const override;
-
- /**
- * Get the Differential coefficient.
- *
- * @return differential coefficient
- */
- double GetD() const override;
-
- /**
- * Get the Feed forward coefficient.
- *
- * @return Feed forward coefficient
- */
- virtual double GetF() const;
-
- /**
- * Set the setpoint for the PIDBase.
- *
- * @param setpoint the desired setpoint
- */
- void SetSetpoint(double setpoint) override;
-
- /**
- * Returns the current setpoint of the PIDBase.
- *
- * @return the current setpoint
- */
- double GetSetpoint() const override;
-
- /**
- * Returns the change in setpoint over time of the PIDBase.
- *
- * @return the change in setpoint over time
- */
- double GetDeltaSetpoint() const;
-
- /**
- * Returns the current difference of the input from the setpoint.
- *
- * @return the current error
- */
- virtual double GetError() const;
-
- /**
- * Returns the current average of the error over the past few iterations.
- *
- * You can specify the number of iterations to average with
- * SetToleranceBuffer() (defaults to 1). This is the same value that is used
- * for OnTarget().
- *
- * @return the average error
- */
- WPI_DEPRECATED("Use a LinearFilter as the input and GetError().")
- virtual double GetAvgError() const;
-
- /**
- * Sets what type of input the PID controller will use.
- */
- virtual void SetPIDSourceType(PIDSourceType pidSource);
-
- /**
- * Returns the type of input the PID controller is using.
- *
- * @return the PID controller input type
- */
- virtual PIDSourceType GetPIDSourceType() const;
-
- /**
- * Set the percentage error which is considered tolerable for use with
- * OnTarget.
- *
- * @param percent error which is tolerable
- */
- WPI_DEPRECATED("Use SetPercentTolerance() instead.")
- virtual void SetTolerance(double percent);
-
- /**
- * Set the absolute error which is considered tolerable for use with
- * OnTarget.
- *
- * @param absTolerance error which is tolerable
- */
- virtual void SetAbsoluteTolerance(double absTolerance);
-
- /**
- * Set the percentage error which is considered tolerable for use with
- * OnTarget.
- *
- * @param percent error which is tolerable
- */
- virtual void SetPercentTolerance(double percent);
-
- /**
- * Set the number of previous error samples to average for tolerancing. When
- * determining whether a mechanism is on target, the user may want to use a
- * rolling average of previous measurements instead of a precise position or
- * velocity. This is useful for noisy sensors which return a few erroneous
- * measurements when the mechanism is on target. However, the mechanism will
- * not register as on target for at least the specified bufLength cycles.
- *
- * @param bufLength Number of previous cycles to average. Defaults to 1.
- */
- WPI_DEPRECATED("Use a LinearDigitalFilter as the input.")
- virtual void SetToleranceBuffer(int bufLength = 1);
-
- /**
- * Return true if the error is within the percentage of the total input range,
- * determined by SetTolerance. This asssumes that the maximum and minimum
- * input were set using SetInput.
- *
- * Currently this just reports on target as the actual value passes through
- * the setpoint. Ideally it should be based on being within the tolerance for
- * some period of time.
- *
- * This will return false until at least one input value has been computed.
- */
- virtual bool OnTarget() const;
-
- /**
- * Reset the previous error, the integral term, and disable the controller.
- */
- void Reset() override;
-
- /**
- * Passes the output directly to SetSetpoint().
- *
- * PIDControllers can be nested by passing a PIDController as another
- * PIDController's output. In that case, the output of the parent controller
- * becomes the input (i.e., the reference) of the child.
- *
- * It is the caller's responsibility to put the data into a valid form for
- * SetSetpoint().
- */
- void PIDWrite(double output) override;
-
- void InitSendable(wpi::SendableBuilder& builder) override;
-
- protected:
- // Is the pid controller enabled
- bool m_enabled = false;
-
- mutable wpi::mutex m_thisMutex;
-
- // Ensures when Disable() is called, PIDWrite() won't run if Calculate()
- // is already running at that time.
- mutable wpi::mutex m_pidWriteMutex;
-
- PIDSource* m_pidInput;
- PIDOutput* m_pidOutput;
- Timer m_setpointTimer;
-
- /**
- * Read the input, calculate the output accordingly, and write to the output.
- * This should only be called by the Notifier.
- */
- virtual void Calculate();
-
- /**
- * Calculate the feed forward term.
- *
- * Both of the provided feed forward calculations are velocity feed forwards.
- * If a different feed forward calculation is desired, the user can override
- * this function and provide his or her own. This function does no
- * synchronization because the PIDBase class only calls it in synchronized
- * code, so be careful if calling it oneself.
- *
- * If a velocity PID controller is being used, the F term should be set to 1
- * over the maximum setpoint for the output. If a position PID controller is
- * being used, the F term should be set to 1 over the maximum speed for the
- * output measured in setpoint units per this controller's update period (see
- * the default period in this class's constructor).
- */
- virtual double CalculateFeedForward();
-
- /**
- * Wraps error around for continuous inputs. The original error is returned if
- * continuous mode is disabled. This is an unsynchronized function.
- *
- * @param error The current error of the PID controller.
- * @return Error for continuous inputs.
- */
- double GetContinuousError(double error) const;
-
- private:
- // Factor for "proportional" control
- double m_P;
-
- // Factor for "integral" control
- double m_I;
-
- // Factor for "derivative" control
- double m_D;
-
- // Factor for "feed forward" control
- double m_F;
-
- // |maximum output|
- double m_maximumOutput = 1.0;
-
- // |minimum output|
- double m_minimumOutput = -1.0;
-
- // Maximum input - limit setpoint to this
- double m_maximumInput = 0;
-
- // Minimum input - limit setpoint to this
- double m_minimumInput = 0;
-
- // input range - difference between maximum and minimum
- double m_inputRange = 0;
-
- // Do the endpoints wrap around? eg. Absolute encoder
- bool m_continuous = false;
-
- // The prior error (used to compute velocity)
- double m_prevError = 0;
-
- // The sum of the errors for use in the integral calc
- double m_totalError = 0;
-
- enum {
- kAbsoluteTolerance,
- kPercentTolerance,
- kNoTolerance
- } m_toleranceType = kNoTolerance;
-
- // The percetage or absolute error that is considered on target.
- double m_tolerance = 0.05;
-
- double m_setpoint = 0;
- double m_prevSetpoint = 0;
- double m_error = 0;
- double m_result = 0;
-
- LinearFilter m_filter{{}, {}};
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/PIDController.h b/wpilibOldCommands/src/main/native/include/frc/PIDController.h
deleted file mode 100644
index 224c5e9dbc..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/PIDController.h
+++ /dev/null
@@ -1,139 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include
-#include
-
-#include "frc/Controller.h"
-#include "frc/Notifier.h"
-#include "frc/PIDBase.h"
-#include "frc/PIDSource.h"
-#include "frc/Timer.h"
-
-namespace frc {
-
-class PIDOutput;
-
-/**
- * Class implements a PID Control Loop.
- *
- * Creates a separate thread which reads the given PIDSource and takes care of
- * the integral calculations, as well as writing the given PIDOutput.
- *
- * This feedback controller runs in discrete time, so time deltas are not used
- * in the integral and derivative calculations. Therefore, the sample rate
- * affects the controller's behavior for a given set of PID constants.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead.
- */
-class PIDController : public PIDBase, public Controller {
- public:
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- * @param period the loop time for doing calculations in seconds. This
- * particularly affects calculations of the integral and
- * differential terms. The default is 0.05 (50ms).
- */
- WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDController(double p, double i, double d, PIDSource* source,
- PIDOutput* output, double period = 0.05);
-
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param f the feedforward coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- * @param period the loop time for doing calculations in seconds. This
- * particularly affects calculations of the integral and
- * differential terms. The default is 0.05 (50ms).
- */
- WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDController(double p, double i, double d, double f, PIDSource* source,
- PIDOutput* output, double period = 0.05);
-
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- * @param period the loop time for doing calculations in seconds. This
- * particularly affects calculations of the integral and
- * differential terms. The default is 0.05 (50ms).
- */
- WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDController(double p, double i, double d, PIDSource& source,
- PIDOutput& output, double period = 0.05);
-
- /**
- * Allocate a PID object with the given constants for P, I, D.
- *
- * @param p the proportional coefficient
- * @param i the integral coefficient
- * @param d the derivative coefficient
- * @param f the feedforward coefficient
- * @param source The PIDSource object that is used to get values
- * @param output The PIDOutput object that is set to the output value
- * @param period the loop time for doing calculations in seconds. This
- * particularly affects calculations of the integral and
- * differential terms. The default is 0.05 (50ms).
- */
- WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDController(double p, double i, double d, double f, PIDSource& source,
- PIDOutput& output, double period = 0.05);
-
- ~PIDController() override;
-
- /**
- * Begin running the PIDController.
- */
- void Enable() override;
-
- /**
- * Stop running the PIDController, this sets the output to zero before
- * stopping.
- */
- void Disable() override;
-
- /**
- * Set the enabled state of the PIDController.
- */
- void SetEnabled(bool enable);
-
- /**
- * Return true if PIDController is enabled.
- */
- bool IsEnabled() const;
-
- /**
- * Reset the previous error, the integral term, and disable the controller.
- */
- void Reset() override;
-
- void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
- std::unique_ptr m_controlLoop;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h b/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h
deleted file mode 100644
index 7af3ec6bc3..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/PIDInterface.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-namespace frc {
-
-/**
- * Interface for PID Control Loop.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated All APIs which use this have been deprecated.
- */
-class PIDInterface {
- public:
- WPI_DEPRECATED("All APIs which use this have been deprecated.")
- PIDInterface() = default;
- PIDInterface(PIDInterface&&) = default;
- PIDInterface& operator=(PIDInterface&&) = default;
-
- virtual void SetPID(double p, double i, double d) = 0;
- virtual double GetP() const = 0;
- virtual double GetI() const = 0;
- virtual double GetD() const = 0;
-
- virtual void SetSetpoint(double setpoint) = 0;
- virtual double GetSetpoint() const = 0;
-
- virtual void Reset() = 0;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h b/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h
deleted file mode 100644
index 3e1e780709..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/PIDOutput.h
+++ /dev/null
@@ -1,22 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-/**
- * PIDOutput interface is a generic output for the PID class.
- *
- * MotorControllers use this class. Users implement this interface to allow for
- * a PIDController to read directly from the inputs.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDOutput {
- public:
- virtual void PIDWrite(double output) = 0;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/PIDSource.h b/wpilibOldCommands/src/main/native/include/frc/PIDSource.h
deleted file mode 100644
index 52990a1e42..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/PIDSource.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-enum class PIDSourceType { kDisplacement, kRate };
-
-/**
- * PIDSource interface is a generic sensor source for the PID class.
- *
- * All sensors that can be used with the PID class will implement the PIDSource
- * that returns a standard value that will be used in the PID code.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDSource {
- public:
- virtual ~PIDSource() = default;
-
- /**
- * Set which parameter you are using as a process control variable.
- *
- * @param pidSource An enum to select the parameter.
- */
- virtual void SetPIDSourceType(PIDSourceType pidSource);
-
- virtual PIDSourceType GetPIDSourceType() const;
-
- virtual double PIDGet() = 0;
-
- protected:
- PIDSourceType m_pidSource = PIDSourceType::kDisplacement;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h b/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h
deleted file mode 100644
index 51fe09802c..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/Button.h
+++ /dev/null
@@ -1,72 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/Trigger.h"
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This class provides an easy way to link commands to OI inputs.
- *
- * It is very easy to link a button to a command. For instance, you could link
- * the trigger button of a joystick to a "score" command.
- *
- * This class represents a subclass of Trigger that is specifically aimed at
- * buttons on an operator interface as a common use case of the more generalized
- * Trigger objects. This is a simple wrapper around Trigger with the method
- * names renamed to fit the Button object use.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Button : public Trigger {
- public:
- Button() = default;
- Button(Button&&) = default;
- Button& operator=(Button&&) = default;
-
- /**
- * Specifies the command to run when a button is first pressed.
- *
- * @param command The pointer to the command to run
- */
- virtual void WhenPressed(Command* command);
-
- /**
- * Specifies the command to be scheduled while the button is pressed.
- *
- * The command will be scheduled repeatedly while the button is pressed and
- * will be canceled when the button is released.
- *
- * @param command The pointer to the command to run
- */
- virtual void WhileHeld(Command* command);
-
- /**
- * Specifies the command to run when the button is released.
- *
- * The command will be scheduled a single time.
- *
- * @param command The pointer to the command to run
- */
- virtual void WhenReleased(Command* command);
-
- /**
- * Cancels the specificed command when the button is pressed.
- *
- * @param command The command to be canceled
- */
- virtual void CancelWhenPressed(Command* command);
-
- /**
- * Toggle the specified command when the button is pressed.
- *
- * @param command The command to be toggled
- */
- virtual void ToggleWhenPressed(Command* command);
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h
deleted file mode 100644
index 0c3ad2049b..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/ButtonScheduler.h
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ButtonScheduler {
- public:
- ButtonScheduler(bool last, Trigger* button, Command* orders);
- virtual ~ButtonScheduler() = default;
-
- ButtonScheduler(ButtonScheduler&&) = default;
- ButtonScheduler& operator=(ButtonScheduler&&) = default;
-
- virtual void Execute() = 0;
- void Start();
-
- protected:
- bool m_pressedLast;
- Trigger* m_button;
- Command* m_command;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h
deleted file mode 100644
index c3938eb4c1..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/CancelButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class CancelButtonScheduler : public ButtonScheduler {
- public:
- CancelButtonScheduler(bool last, Trigger* button, Command* orders);
- ~CancelButtonScheduler() override = default;
-
- CancelButtonScheduler(CancelButtonScheduler&&) = default;
- CancelButtonScheduler& operator=(CancelButtonScheduler&&) = default;
-
- void Execute() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h
deleted file mode 100644
index 721688fa52..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/HeldButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class HeldButtonScheduler : public ButtonScheduler {
- public:
- HeldButtonScheduler(bool last, Trigger* button, Command* orders);
- ~HeldButtonScheduler() override = default;
-
- HeldButtonScheduler(HeldButtonScheduler&&) = default;
- HeldButtonScheduler& operator=(HeldButtonScheduler&&) = default;
-
- void Execute() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h b/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h
deleted file mode 100644
index 05c8348263..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/InternalButton.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * This Button is intended to be used within a program. The programmer can
- * manually set its value. Also includes a setting for whether or not it should
- * invert its value.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class InternalButton : public Button {
- public:
- InternalButton() = default;
- explicit InternalButton(bool inverted);
- ~InternalButton() override = default;
-
- InternalButton(InternalButton&&) = default;
- InternalButton& operator=(InternalButton&&) = default;
-
- void SetInverted(bool inverted);
- void SetPressed(bool pressed);
-
- bool Get() override;
-
- private:
- bool m_pressed = false;
- bool m_inverted = false;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h b/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h
deleted file mode 100644
index 7e92cc1a63..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/JoystickButton.h
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/GenericHID.h"
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A Button} that gets its state from a GenericHID.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class JoystickButton : public Button {
- public:
- JoystickButton(GenericHID* joystick, int buttonNumber);
- ~JoystickButton() override = default;
-
- JoystickButton(JoystickButton&&) = default;
- JoystickButton& operator=(JoystickButton&&) = default;
-
- bool Get() override;
-
- private:
- GenericHID* m_joystick;
- int m_buttonNumber;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h b/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h
deleted file mode 100644
index e277230557..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/NetworkButton.h
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include
-#include
-
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A that uses a NetworkTable boolean field.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class NetworkButton : public Button {
- public:
- NetworkButton(std::string_view tableName, std::string_view field);
- NetworkButton(std::shared_ptr table,
- std::string_view field);
- ~NetworkButton() override = default;
-
- NetworkButton(NetworkButton&&) = default;
- NetworkButton& operator=(NetworkButton&&) = default;
-
- bool Get() override;
-
- private:
- nt::NetworkTableEntry m_entry;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h b/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h
deleted file mode 100644
index 72ff50a8ad..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/POVButton.h
+++ /dev/null
@@ -1,39 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/GenericHID.h"
-#include "frc/buttons/Button.h"
-
-namespace frc {
-
-/**
- * A Button that gets its state from a POV on a GenericHID.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class POVButton : public Button {
- public:
- /**
- * Creates a POV button for triggering commands.
- *
- * @param joystick The GenericHID object that has the POV
- * @param angle The desired angle in degrees (e.g. 90, 270)
- * @param povNumber The POV number (@see GenericHID#GetPOV)
- */
- POVButton(GenericHID& joystick, int angle, int povNumber = 0);
- ~POVButton() override = default;
-
- POVButton(POVButton&&) = default;
- POVButton& operator=(POVButton&&) = default;
-
- bool Get() override;
-
- private:
- GenericHID* m_joystick;
- int m_angle;
- int m_povNumber;
-};
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h
deleted file mode 100644
index 378d2c5f5c..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/PressedButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class PressedButtonScheduler : public ButtonScheduler {
- public:
- PressedButtonScheduler(bool last, Trigger* button, Command* orders);
- ~PressedButtonScheduler() override = default;
-
- PressedButtonScheduler(PressedButtonScheduler&&) = default;
- PressedButtonScheduler& operator=(PressedButtonScheduler&&) = default;
-
- void Execute() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
deleted file mode 100644
index 6ed53eecbc..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ReleasedButtonScheduler : public ButtonScheduler {
- public:
- ReleasedButtonScheduler(bool last, Trigger* button, Command* orders);
- ~ReleasedButtonScheduler() override = default;
-
- ReleasedButtonScheduler(ReleasedButtonScheduler&&) = default;
- ReleasedButtonScheduler& operator=(ReleasedButtonScheduler&&) = default;
-
- void Execute() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h b/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
deleted file mode 100644
index 8df27a9b27..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
+++ /dev/null
@@ -1,25 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/buttons/ButtonScheduler.h"
-
-namespace frc {
-
-class Trigger;
-class Command;
-
-class ToggleButtonScheduler : public ButtonScheduler {
- public:
- ToggleButtonScheduler(bool last, Trigger* button, Command* orders);
- ~ToggleButtonScheduler() override = default;
-
- ToggleButtonScheduler(ToggleButtonScheduler&&) = default;
- ToggleButtonScheduler& operator=(ToggleButtonScheduler&&) = default;
-
- void Execute() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h b/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h
deleted file mode 100644
index 4edceaa10b..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/buttons/Trigger.h
+++ /dev/null
@@ -1,55 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-#include
-
-namespace frc {
-
-class Command;
-
-/**
- * This class provides an easy way to link commands to inputs.
- *
- * It is very easy to link a polled input to a command. For instance, you could
- * link the trigger button of a joystick to a "score" command or an encoder
- * reaching a particular value.
- *
- * It is encouraged that teams write a subclass of Trigger if they want to have
- * something unusual (for instance, if they want to react to the user holding
- * a button while the robot is reading a certain sensor input). For this, they
- * only have to write the Trigger::Get() method to get the full functionality of
- * the Trigger class.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Trigger : public wpi::Sendable, public wpi::SendableHelper {
- public:
- Trigger() = default;
- ~Trigger() override = default;
-
- Trigger(const Trigger& rhs);
- Trigger& operator=(const Trigger& rhs);
- Trigger(Trigger&& rhs);
- Trigger& operator=(Trigger&& rhs);
-
- bool Grab();
- virtual bool Get() = 0;
- void WhenActive(Command* command);
- void WhileActive(Command* command);
- void WhenInactive(Command* command);
- void CancelWhenActive(Command* command);
- void ToggleWhenActive(Command* command);
-
- void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
- std::atomic_bool m_sendablePressed{false};
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/Command.h b/wpilibOldCommands/src/main/native/include/frc/commands/Command.h
deleted file mode 100644
index 3e43cff1c2..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/Command.h
+++ /dev/null
@@ -1,490 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-class CommandGroup;
-
-/**
- * The Command class is at the very core of the entire command framework.
- *
- * Every command can be started with a call to Start(). Once a command is
- * started it will call Initialize(), and then will repeatedly call Execute()
- * until the IsFinished() returns true. Once it does,End() will be called.
- *
- * However, if at any point while it is running Cancel() is called, then the
- * command will be stopped and Interrupted() will be called.
- *
- * If a command uses a Subsystem, then it should specify that it does so by
- * calling the Requires() method in its constructor. Note that a Command may
- * have multiple requirements, and Requires() should be called for each one.
- *
- * If a command is running and a new command with shared requirements is
- * started, then one of two things will happen. If the active command is
- * interruptible, then Cancel() will be called and the command will be removed
- * to make way for the new one. If the active command is not interruptible, the
- * other one will not even be started, and the active one will continue
- * functioning.
- *
- * This class is provided by the OldCommands VendorDep
- * *
- * @see CommandGroup
- * @see Subsystem
- */
-class Command : public wpi::Sendable, public wpi::SendableHelper {
- friend class CommandGroup;
- friend class Scheduler;
-
- public:
- /**
- * Creates a new command.
- *
- * The name of this command will be default.
- */
- Command();
-
- /**
- * Creates a new command with the given name and no timeout.
- *
- * @param name the name for this command
- */
- explicit Command(std::string_view name);
-
- /**
- * Creates a new command with the given timeout and a default name.
- *
- * @param timeout the time before this command "times out"
- * @see IsTimedOut()
- */
- explicit Command(units::second_t timeout);
-
- /**
- * Creates a new command with the given timeout and a default name.
- *
- * @param subsystem the subsystem that the command requires
- */
- explicit Command(Subsystem& subsystem);
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time before this command "times out"
- * @see IsTimedOut()
- */
- Command(std::string_view name, units::second_t timeout);
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param name the name of the command
- * @param subsystem the subsystem that the command requires
- */
- Command(std::string_view name, Subsystem& subsystem);
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param timeout the time before this command "times out"
- * @param subsystem the subsystem that the command requires @see IsTimedOut()
- */
- Command(units::second_t timeout, Subsystem& subsystem);
-
- /**
- * Creates a new command with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time before this command "times out"
- * @param subsystem the subsystem that the command requires @see IsTimedOut()
- */
- Command(std::string_view name, units::second_t timeout, Subsystem& subsystem);
-
- ~Command() override = default;
-
- Command(Command&&) = default;
- Command& operator=(Command&&) = default;
-
- /**
- * Returns the time since this command was initialized.
- *
- * This function will work even if there is no specified timeout.
- *
- * @return the time since this command was initialized.
- */
- units::second_t TimeSinceInitialized() const;
-
- /**
- * This method specifies that the given Subsystem is used by this command.
- *
- * This method is crucial to the functioning of the Command System in general.
- *
- * Note that the recommended way to call this method is in the constructor.
- *
- * @param subsystem The Subsystem required
- * @see Subsystem
- */
- void Requires(Subsystem* subsystem);
-
- /**
- * Starts up the command. Gets the command ready to start.
- *
- * Note that the command will eventually start, however it will not
- * necessarily do so immediately, and may in fact be canceled before
- * initialize is even called.
- */
- void Start();
-
- /**
- * The run method is used internally to actually run the commands.
- *
- * @return Whether or not the command should stay within the Scheduler.
- */
- bool Run();
-
- /**
- * This will cancel the current command.
- *
- * This will cancel the current command eventually. It can be called multiple
- * times. And it can be called when the command is not running. If the command
- * is running though, then the command will be marked as canceled and
- * eventually removed.
- *
- * A command can not be canceled if it is a part of a command group, you must
- * cancel the command group instead.
- */
- void Cancel();
-
- /**
- * Returns whether or not the command is running.
- *
- * This may return true even if the command has just been canceled, as it may
- * not have yet called Interrupted().
- *
- * @return whether or not the command is running
- */
- bool IsRunning() const;
-
- /**
- * Returns whether or not the command has been initialized.
- *
- * @return whether or not the command has been initialized.
- */
- bool IsInitialized() const;
-
- /**
- * Returns whether or not the command has completed running.
- *
- * @return whether or not the command has completed running.
- */
- bool IsCompleted() const;
-
- /**
- * Returns whether or not this has been canceled.
- *
- * @return whether or not this has been canceled
- */
- bool IsCanceled() const;
-
- /**
- * Returns whether or not this command can be interrupted.
- *
- * @return whether or not this command can be interrupted
- */
- bool IsInterruptible() const;
-
- /**
- * Sets whether or not this command can be interrupted.
- *
- * @param interruptible whether or not this command can be interrupted
- */
- void SetInterruptible(bool interruptible);
-
- /**
- * Checks if the command requires the given Subsystem.
- *
- * @param subsystem the subsystem
- * @return whether or not the subsystem is required (false if given nullptr)
- */
- bool DoesRequire(Subsystem* subsystem) const;
-
- using SubsystemSet = wpi::SmallPtrSetImpl;
-
- /**
- * Returns the requirements (as an std::set of Subsystem pointers) of this
- * command.
- *
- * @return The requirements (as an std::set of Subsystem pointers) of this
- * command
- */
- const SubsystemSet& GetRequirements() const;
-
- /**
- * Returns the CommandGroup that this command is a part of.
- *
- * Will return null if this Command is not in a group.
- *
- * @return The CommandGroup that this command is a part of (or null if not in
- * group)
- */
- CommandGroup* GetGroup() const;
-
- /**
- * Sets whether or not this Command should run when the robot is disabled.
- *
- * By default a command will not run when the robot is disabled, and will in
- * fact be canceled.
- *
- * @param run Whether this command should run when the robot is disabled.
- */
- void SetRunWhenDisabled(bool run);
-
- /**
- * Returns whether or not this Command will run when the robot is disabled, or
- * if it will cancel itself.
- *
- * @return Whether this Command will run when the robot is disabled, or if it
- * will cancel itself.
- */
- bool WillRunWhenDisabled() const;
-
- /**
- * Get the ID (sequence number) for this command.
- *
- * The ID is a unique sequence number that is incremented for each command.
- *
- * @return The ID of this command
- */
- int GetID() const;
-
- protected:
- /**
- * Sets the timeout of this command.
- *
- * @param timeout the timeout
- * @see IsTimedOut()
- */
- void SetTimeout(units::second_t timeout);
-
- /**
- * Returns whether or not the TimeSinceInitialized() method returns a number
- * which is greater than or equal to the timeout for the command.
- *
- * If there is no timeout, this will always return false.
- *
- * @return whether the time has expired
- */
- bool IsTimedOut() const;
-
- /**
- * If changes are locked, then this will generate a CommandIllegalUse error.
- *
- * @param message The message to report on error (it is appended by a default
- * message)
- * @return True if assert passed, false if assert failed.
- */
- bool AssertUnlocked(std::string_view message);
-
- /**
- * Sets the parent of this command. No actual change is made to the group.
- *
- * @param parent the parent
- */
- void SetParent(CommandGroup* parent);
-
- /**
- * Returns whether the command has a parent.
- *
- * @param True if the command has a parent.
- */
- bool IsParented() const;
-
- /**
- * Clears list of subsystem requirements.
- *
- * This is only used by ConditionalCommand so canceling the chosen command
- * works properly in CommandGroup.
- */
- void ClearRequirements();
-
- /**
- * The initialize method is called the first time this Command is run after
- * being started.
- */
- virtual void Initialize();
-
- /**
- * The execute method is called repeatedly until this Command either finishes
- * or is canceled.
- */
- virtual void Execute();
-
- /**
- * Returns whether this command is finished.
- *
- * If it is, then the command will be removed and End() will be called.
- *
- * It may be useful for a team to reference the IsTimedOut() method for
- * time-sensitive commands.
- *
- * Returning false will result in the command never ending automatically.
- * It may still be canceled manually or interrupted by another command.
- * Returning true will result in the command executing once and finishing
- * immediately. We recommend using InstantCommand for this.
- *
- * @return Whether this command is finished.
- * @see IsTimedOut()
- */
- virtual bool IsFinished() = 0;
-
- /**
- * Called when the command ended peacefully.
- *
- * This is where you may want to wrap up loose ends, like shutting off a motor
- * that was being used in the command.
- */
- virtual void End();
-
- /**
- * Called when the command ends because somebody called Cancel() or another
- * command shared the same requirements as this one, and booted it out.
- *
- * This is where you may want to wrap up loose ends, like shutting off a motor
- * that was being used in the command.
- *
- * Generally, it is useful to simply call the End() method within this method,
- * as done here.
- */
- virtual void Interrupted();
-
- virtual void _Initialize();
- virtual void _Interrupted();
- virtual void _Execute();
- virtual void _End();
-
- /**
- * This works like Cancel(), except that it doesn't throw an exception if it
- * is a part of a command group.
- *
- * Should only be called by the parent command group.
- */
- virtual void _Cancel();
-
- friend class ConditionalCommand;
-
- public:
- /**
- * Gets the name of this Command.
- *
- * @return Name
- */
- std::string GetName() const;
-
- /**
- * Sets the name of this Command.
- *
- * @param name name
- */
- void SetName(std::string_view name);
-
- /**
- * Gets the subsystem name of this Command.
- *
- * @return Subsystem name
- */
- std::string GetSubsystem() const;
-
- /**
- * Sets the subsystem name of this Command.
- *
- * @param subsystem subsystem name
- */
- void SetSubsystem(std::string_view subsystem);
-
- private:
- /**
- * Prevents further changes from being made.
- */
- void LockChanges();
-
- /**
- * Called when the command has been removed.
- *
- * This will call Interrupted() or End().
- */
- void Removed();
-
- /**
- * This is used internally to mark that the command has been started.
- *
- * The lifecycle of a command is:
- *
- * StartRunning() is called. Run() is called (multiple times potentially).
- * Removed() is called.
- *
- * It is very important that StartRunning() and Removed() be called in order
- * or some assumptions of the code will be broken.
- */
- void StartRunning();
-
- /**
- * Called to indicate that the timer should start.
- *
- * This is called right before Initialize() is, inside the Run() method.
- */
- void StartTiming();
-
- // The time since this command was initialized
- units::second_t m_startTime = -1_s;
-
- // The time (in seconds) before this command "times out" (-1 if no timeout)
- units::second_t m_timeout;
-
- // Whether or not this command has been initialized
- bool m_initialized = false;
-
- // The requirements (or null if no requirements)
- wpi::SmallPtrSet m_requirements;
-
- // Whether or not it is running
- bool m_running = false;
-
- // Whether or not it is interruptible
- bool m_interruptible = true;
-
- // Whether or not it has been canceled
- bool m_canceled = false;
-
- // Whether or not it has been locked
- bool m_locked = false;
-
- // Whether this command should run when the robot is disabled
- bool m_runWhenDisabled = false;
-
- // The CommandGroup this is in
- CommandGroup* m_parent = nullptr;
-
- // Whether or not this command has completed running
- bool m_completed = false;
-
- int m_commandID = m_commandCounter++;
- static int m_commandCounter;
-
- public:
- void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h b/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h
deleted file mode 100644
index f48ddbfa1d..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroup.h
+++ /dev/null
@@ -1,180 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include
-
-#include "frc/commands/Command.h"
-#include "frc/commands/CommandGroupEntry.h"
-
-namespace frc {
-
-/**
- * A CommandGroup is a list of commands which are executed in sequence.
- *
- * Commands in a CommandGroup are added using the AddSequential() method and are
- * called sequentially. CommandGroups are themselves Commands and can be given
- * to other CommandGroups.
- *
- * CommandGroups will carry all of the requirements of their Command
- * subcommands. Additional requirements can be specified by calling Requires()
- * normally in the constructor.
- *
- * CommandGroups can also execute commands in parallel, simply by adding them
- * using AddParallel().
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Subsystem
- */
-class CommandGroup : public Command {
- public:
- CommandGroup() = default;
-
- /**
- * Creates a new CommandGroup with the given name.
- *
- * @param name The name for this command group
- */
- explicit CommandGroup(std::string_view name);
-
- ~CommandGroup() override = default;
-
- CommandGroup(CommandGroup&&) = default;
- CommandGroup& operator=(CommandGroup&&) = default;
-
- /**
- * Adds a new Command to the group. The Command will be started after all the
- * previously added Commands.
- *
- * Note that any requirements the given Command has will be added to the
- * group. For this reason, a Command's requirements can not be changed after
- * being added to a group.
- *
- * It is recommended that this method be called in the constructor.
- *
- * @param command The Command to be added
- */
- void AddSequential(Command* command);
-
- /**
- * Adds a new Command to the group with a given timeout. The Command will be
- * started after all the previously added commands.
- *
- * Once the Command is started, it will be run until it finishes or the time
- * expires, whichever is sooner. Note that the given Command will have no
- * knowledge that it is on a timer.
- *
- * Note that any requirements the given Command has will be added to the
- * group. For this reason, a Command's requirements can not be changed after
- * being added to a group.
- *
- * It is recommended that this method be called in the constructor.
- *
- * @param command The Command to be added
- * @param timeout The timeout
- */
- void AddSequential(Command* command, units::second_t timeout);
-
- /**
- * Adds a new child Command to the group. The Command will be started after
- * all the previously added Commands.
- *
- * Instead of waiting for the child to finish, a CommandGroup will have it run
- * at the same time as the subsequent Commands. The child will run until
- * either it finishes, a new child with conflicting requirements is started,
- * or the main sequence runs a Command with conflicting requirements. In the
- * latter two cases, the child will be canceled even if it says it can't be
- * interrupted.
- *
- * Note that any requirements the given Command has will be added to the
- * group. For this reason, a Command's requirements can not be changed after
- * being added to a group.
- *
- * It is recommended that this method be called in the constructor.
- *
- * @param command The command to be added
- */
- void AddParallel(Command* command);
-
- /**
- * Adds a new child Command to the group with the given timeout. The Command
- * will be started after all the previously added Commands.
- *
- * Once the Command is started, it will run until it finishes, is interrupted,
- * or the time expires, whichever is sooner. Note that the given Command will
- * have no knowledge that it is on a timer.
- *
- * Instead of waiting for the child to finish, a CommandGroup will have it run
- * at the same time as the subsequent Commands. The child will run until
- * either it finishes, the timeout expires, a new child with conflicting
- * requirements is started, or the main sequence runs a Command with
- * conflicting requirements. In the latter two cases, the child will be
- * canceled even if it says it can't be interrupted.
- *
- * Note that any requirements the given Command has will be added to the
- * group. For this reason, a Command's requirements can not be changed after
- * being added to a group.
- *
- * It is recommended that this method be called in the constructor.
- *
- * @param command The command to be added
- * @param timeout The timeout
- */
- void AddParallel(Command* command, units::second_t timeout);
-
- bool IsInterruptible() const;
-
- int GetSize() const;
-
- protected:
- /**
- * Can be overridden by teams.
- */
- void Initialize() override;
-
- /**
- * Can be overridden by teams.
- */
- void Execute() override;
-
- /**
- * Can be overridden by teams.
- */
- bool IsFinished() override;
-
- /**
- * Can be overridden by teams.
- */
- void End() override;
-
- /**
- * Can be overridden by teams.
- */
- void Interrupted() override;
-
- void _Initialize() override;
- void _Execute() override;
- void _End() override;
- void _Interrupted() override;
-
- private:
- void CancelConflicts(Command* command);
-
- // The commands in this group (stored in entries)
- std::vector m_commands;
-
- // The active children in this group (stored in entries)
- std::vector m_children;
-
- // The current command, -1 signifies that none have been run
- int m_currentCommandIndex = -1;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h b/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h
deleted file mode 100644
index b6162f3819..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/CommandGroupEntry.h
+++ /dev/null
@@ -1,35 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-namespace frc {
-
-class Command;
-
-class CommandGroupEntry {
- public:
- enum Sequence {
- kSequence_InSequence,
- kSequence_BranchPeer,
- kSequence_BranchChild
- };
-
- CommandGroupEntry() = default;
- CommandGroupEntry(Command* command, Sequence state,
- units::second_t timeout = -1_s);
-
- CommandGroupEntry(CommandGroupEntry&&) = default;
- CommandGroupEntry& operator=(CommandGroupEntry&&) = default;
-
- bool IsTimedOut() const;
-
- units::second_t m_timeout = -1_s;
- Command* m_command = nullptr;
- Sequence m_state = kSequence_InSequence;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h
deleted file mode 100644
index 46e73cb23b..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/ConditionalCommand.h
+++ /dev/null
@@ -1,83 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A ConditionalCommand is a Command that starts one of two commands.
- *
- * A ConditionalCommand uses the Condition method to determine whether it should
- * run onTrue or onFalse.
- *
- * A ConditionalCommand adds the proper Command to the Scheduler during
- * Initialize() and then IsFinished() will return true once that Command has
- * finished executing.
- *
- * If no Command is specified for onFalse, the occurrence of that condition
- * will be a no-op.
- *
- * A ConditionalCommand will require the superset of subsystems of the onTrue
- * and onFalse commands.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see Command
- * @see Scheduler
- */
-class ConditionalCommand : public Command {
- public:
- /**
- * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
- *
- * @param onTrue The Command to execute if Condition() returns true
- * @param onFalse The Command to execute if Condition() returns false
- */
- explicit ConditionalCommand(Command* onTrue, Command* onFalse = nullptr);
-
- /**
- * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
- *
- * @param name The name for this command group
- * @param onTrue The Command to execute if Condition() returns true
- * @param onFalse The Command to execute if Condition() returns false
- */
- ConditionalCommand(std::string_view name, Command* onTrue,
- Command* onFalse = nullptr);
-
- ~ConditionalCommand() override = default;
-
- ConditionalCommand(ConditionalCommand&&) = default;
- ConditionalCommand& operator=(ConditionalCommand&&) = default;
-
- protected:
- /**
- * The Condition to test to determine which Command to run.
- *
- * @return true if m_onTrue should be run or false if m_onFalse should be run.
- */
- virtual bool Condition() = 0;
-
- void _Initialize() override;
- void _Cancel() override;
- bool IsFinished() override;
- void _Interrupted() override;
-
- private:
- // The Command to execute if Condition() returns true
- Command* m_onTrue;
-
- // The Command to execute if Condition() returns false
- Command* m_onFalse;
-
- // Stores command chosen by condition
- Command* m_chosenCommand = nullptr;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h
deleted file mode 100644
index f1683eb42f..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/InstantCommand.h
+++ /dev/null
@@ -1,91 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include "frc/commands/Command.h"
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-/**
- * This command will execute once, then finish immediately afterward.
- *
- * Subclassing InstantCommand is shorthand for returning true from IsFinished().
- *
- * This class is provided by the OldCommands VendorDep
- */
-class InstantCommand : public Command {
- public:
- /**
- * Creates a new InstantCommand with the given name.
- *
- * @param name The name for this command
- */
- explicit InstantCommand(std::string_view name);
-
- /**
- * Creates a new InstantCommand with the given requirement.
- *
- * @param subsystem The subsystem that the command requires
- */
- explicit InstantCommand(Subsystem& subsystem);
-
- /**
- * Creates a new InstantCommand with the given name.
- *
- * @param name The name for this command
- * @param subsystem The subsystem that the command requires
- */
- InstantCommand(std::string_view name, Subsystem& subsystem);
-
- /**
- * Create a command that calls the given function when run.
- *
- * @param func The function to run when Initialize() is run.
- */
- explicit InstantCommand(std::function func);
-
- /**
- * Create a command that calls the given function when run.
- *
- * @param subsystem The subsystems that this command runs on.
- * @param func The function to run when Initialize() is run.
- */
- InstantCommand(Subsystem& subsystem, std::function func);
-
- /**
- * Create a command that calls the given function when run.
- *
- * @param name The name of the command.
- * @param func The function to run when Initialize() is run.
- */
- InstantCommand(std::string_view name, std::function func);
-
- /**
- * Create a command that calls the given function when run.
- *
- * @param name The name of the command.
- * @param subsystem The subsystems that this command runs on.
- * @param func The function to run when Initialize() is run.
- */
- InstantCommand(std::string_view name, Subsystem& subsystem,
- std::function func);
-
- InstantCommand() = default;
- ~InstantCommand() override = default;
-
- InstantCommand(InstantCommand&&) = default;
- InstantCommand& operator=(InstantCommand&&) = default;
-
- protected:
- std::function m_func = nullptr;
- void _Initialize() override;
- bool IsFinished() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h
deleted file mode 100644
index ba8aa6eaa4..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/PIDCommand.h
+++ /dev/null
@@ -1,79 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include "frc/PIDController.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This class defines aCommand which interacts heavily with a PID loop.
- *
- * It provides some convenience methods to run an internal PIDController . It
- * will also start and stop said PIDController when the PIDCommand is first
- * initialized and ended/interrupted.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDCommand : public Command, public PIDOutput, public PIDSource {
- public:
- PIDCommand(std::string_view name, double p, double i, double d);
- PIDCommand(std::string_view name, double p, double i, double d,
- double period);
- PIDCommand(std::string_view name, double p, double i, double d, double f,
- double period);
- PIDCommand(double p, double i, double d);
- PIDCommand(double p, double i, double d, double period);
- PIDCommand(double p, double i, double d, double f, double period);
- PIDCommand(std::string_view name, double p, double i, double d,
- Subsystem& subsystem);
- PIDCommand(std::string_view name, double p, double i, double d, double period,
- Subsystem& subsystem);
- PIDCommand(std::string_view name, double p, double i, double d, double f,
- double period, Subsystem& subsystem);
- PIDCommand(double p, double i, double d, Subsystem& subsystem);
- PIDCommand(double p, double i, double d, double period, Subsystem& subsystem);
- PIDCommand(double p, double i, double d, double f, double period,
- Subsystem& subsystem);
- ~PIDCommand() override = default;
-
- PIDCommand(PIDCommand&&) = default;
- PIDCommand& operator=(PIDCommand&&) = default;
-
- void SetSetpointRelative(double deltaSetpoint);
-
- // PIDOutput interface
- void PIDWrite(double output) override;
-
- // PIDSource interface
- double PIDGet() override;
-
- protected:
- std::shared_ptr GetPIDController() const;
- void _Initialize() override;
- void _Interrupted() override;
- void _End() override;
- void SetSetpoint(double setpoint);
- double GetSetpoint() const;
- double GetPosition();
-
- virtual double ReturnPIDInput() = 0;
- virtual void UsePIDOutput(double output) = 0;
-
- private:
- // The internal PIDController
- std::shared_ptr m_controller;
-
- public:
- void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h b/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h
deleted file mode 100644
index b66ad38f53..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/PIDSubsystem.h
+++ /dev/null
@@ -1,234 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include "frc/PIDController.h"
-#include "frc/PIDOutput.h"
-#include "frc/PIDSource.h"
-#include "frc/commands/Subsystem.h"
-
-namespace frc {
-
-/**
- * This class is designed to handle the case where there is a Subsystem which
- * uses a single PIDController almost constantly (for instance, an elevator
- * which attempts to stay at a constant height).
- *
- * It provides some convenience methods to run an internal PIDController. It
- * also allows access to the internal PIDController in order to give total
- * control to the programmer.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource {
- public:
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, and D values.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- PIDSubsystem(std::string_view name, double p, double i, double d);
-
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feedforward value
- */
- PIDSubsystem(std::string_view name, double p, double i, double d, double f);
-
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
- *
- * It will also space the time between PID loop calculations to be equal to
- * the given period.
- *
- * @param name the name
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feedfoward value
- * @param period the time (in seconds) between calculations
- */
- PIDSubsystem(std::string_view name, double p, double i, double d, double f,
- double period);
-
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, and D values.
- *
- * It will use the class name as its name.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- */
- PIDSubsystem(double p, double i, double d);
-
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
- *
- * It will use the class name as its name.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feedforward value
- */
- PIDSubsystem(double p, double i, double d, double f);
-
- /**
- * Instantiates a PIDSubsystem that will use the given P, I, D, and F values.
- *
- * It will use the class name as its name. It will also space the time
- * between PID loop calculations to be equal to the given period.
- *
- * @param p the proportional value
- * @param i the integral value
- * @param d the derivative value
- * @param f the feedforward value
- * @param period the time (in seconds) between calculations
- */
- PIDSubsystem(double p, double i, double d, double f, double period);
-
- ~PIDSubsystem() override = default;
-
- PIDSubsystem(PIDSubsystem&&) = default;
- PIDSubsystem& operator=(PIDSubsystem&&) = default;
-
- /**
- * Enables the internal PIDController.
- */
- void Enable();
-
- /**
- * Disables the internal PIDController.
- */
- void Disable();
-
- // PIDOutput interface
- void PIDWrite(double output) override;
-
- // PIDSource interface
-
- double PIDGet() override;
-
- /**
- * Sets the setpoint to the given value.
- *
- * If SetRange() was called, then the given setpoint will be trimmed to fit
- * within the range.
- *
- * @param setpoint the new setpoint
- */
- void SetSetpoint(double setpoint);
-
- /**
- * Adds the given value to the setpoint.
- *
- * If SetRange() was used, then the bounds will still be honored by this
- * method.
- *
- * @param deltaSetpoint the change in the setpoint
- */
- void SetSetpointRelative(double deltaSetpoint);
-
- /**
- * Sets the maximum and minimum values expected from the input.
- *
- * @param minimumInput the minimum value expected from the input
- * @param maximumInput the maximum value expected from the output
- */
- void SetInputRange(double minimumInput, double maximumInput);
-
- /**
- * Sets the maximum and minimum values to write.
- *
- * @param minimumOutput the minimum value to write to the output
- * @param maximumOutput the maximum value to write to the output
- */
- void SetOutputRange(double minimumOutput, double maximumOutput);
-
- /**
- * Return the current setpoint.
- *
- * @return The current setpoint
- */
- double GetSetpoint();
-
- /**
- * Returns the current position.
- *
- * @return the current position
- */
- double GetPosition();
-
- /**
- * Returns the current rate.
- *
- * @return the current rate
- */
- double GetRate();
-
- /**
- * Set the absolute error which is considered tolerable for use with
- * OnTarget.
- *
- * @param absValue absolute error which is tolerable
- */
- virtual void SetAbsoluteTolerance(double absValue);
-
- /**
- * Set the percentage error which is considered tolerable for use with
- * OnTarget().
- *
- * @param percent percentage error which is tolerable
- */
- virtual void SetPercentTolerance(double percent);
-
- /**
- * Return true if the error is within the percentage of the total input range,
- * determined by SetTolerance().
- *
- * This asssumes that the maximum and minimum input were set using SetInput().
- * Use OnTarget() in the IsFinished() method of commands that use this
- * subsystem.
- *
- * Currently this just reports on target as the actual value passes through
- * the setpoint. Ideally it should be based on being within the tolerance for
- * some period of time.
- *
- * @return True if the error is within the percentage tolerance of the input
- * range
- */
- virtual bool OnTarget() const;
-
- protected:
- /**
- * Returns the PIDController used by this PIDSubsystem.
- *
- * Use this if you would like to fine tune the PID loop.
- *
- * @return The PIDController used by this PIDSubsystem
- */
- std::shared_ptr GetPIDController();
-
- virtual double ReturnPIDInput() = 0;
- virtual void UsePIDOutput(double output) = 0;
-
- private:
- // The internal PIDController
- std::shared_ptr m_controller;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h
deleted file mode 100644
index b72b4c9d44..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/PrintCommand.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-#include "frc/commands/InstantCommand.h"
-
-namespace frc {
-
-/**
- * A PrintCommand is a command which prints out a string when it is initialized,
- * and then immediately finishes. It is useful if you want a CommandGroup to
- * print out a string when it reaches a certain point.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class PrintCommand : public InstantCommand {
- public:
- explicit PrintCommand(std::string_view message);
- ~PrintCommand() override = default;
-
- PrintCommand(PrintCommand&&) = default;
- PrintCommand& operator=(PrintCommand&&) = default;
-
- protected:
- void Initialize() override;
-
- private:
- std::string m_message;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h b/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h
deleted file mode 100644
index 1c67df3c50..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/Scheduler.h
+++ /dev/null
@@ -1,106 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-#include
-
-namespace frc {
-
-class ButtonScheduler;
-class Command;
-class Subsystem;
-
-/**
- * The Scheduler is a singleton which holds the top-level running commands. It
- * is in charge of both calling the command's run() method and to make sure that
- * there are no two commands with conflicting requirements running.
- *
- * It is fine if teams wish to take control of the Scheduler themselves, all
- * that needs to be done is to call frc::Scheduler::getInstance()->run() often
- * to have Commands function correctly. However, this is already done for you if
- * you use the CommandBased Robot template.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Scheduler : public nt::NTSendable, public wpi::SendableHelper {
- public:
- /**
- * Returns the Scheduler, creating it if one does not exist.
- *
- * @return the Scheduler
- */
- static Scheduler* GetInstance();
-
- /**
- * Add a command to be scheduled later.
- *
- * In any pass through the scheduler, all commands are added to the additions
- * list, then at the end of the pass, they are all scheduled.
- *
- * @param command The command to be scheduled
- */
- void AddCommand(Command* command);
-
- void AddButton(ButtonScheduler* button);
-
- /**
- * Registers a Subsystem to this Scheduler, so that the Scheduler might know
- * if a default Command needs to be run.
- *
- * All Subsystems should call this.
- *
- * @param subsystem the system
- */
- void RegisterSubsystem(Subsystem* subsystem);
-
- /**
- * Runs a single iteration of the loop.
- *
- * This method should be called often in order to have a functioning
- * Command system. The loop has five stages:
- *
- *
- * - Poll the Buttons
- * - Execute/Remove the Commands
- * - Send values to SmartDashboard
- * - Add Commands
- * - Add Defaults
- *
- */
- void Run();
-
- /**
- * Removes the Command from the Scheduler.
- *
- * @param command the command to remove
- */
- void Remove(Command* command);
-
- void RemoveAll();
-
- /**
- * Completely resets the scheduler. Undefined behavior if running.
- */
- void ResetAll();
-
- void SetEnabled(bool enabled);
-
- void InitSendable(nt::NTSendableBuilder& builder) override;
-
- private:
- Scheduler();
- ~Scheduler() override;
-
- Scheduler(Scheduler&&) = default;
- Scheduler& operator=(Scheduler&&) = default;
-
- struct Impl;
- std::unique_ptr m_impl;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h
deleted file mode 100644
index 2186fe5924..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/StartCommand.h
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include "frc/commands/InstantCommand.h"
-
-namespace frc {
-
-/**
- * A PrintCommand is a command which prints out a string when it is initialized,
- * and then immediately finishes. It is useful if you want a CommandGroup to
- * print out a string when it reaches a certain point.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class StartCommand : public InstantCommand {
- public:
- explicit StartCommand(Command* commandToStart);
- ~StartCommand() override = default;
-
- StartCommand(StartCommand&&) = default;
- StartCommand& operator=(StartCommand&&) = default;
-
- protected:
- void Initialize() override;
-
- private:
- Command* m_commandToFork;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h b/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h
deleted file mode 100644
index 6357f0cee3..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/Subsystem.h
+++ /dev/null
@@ -1,207 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-#include
-
-#include
-#include
-
-namespace frc {
-
-class Command;
-
-/**
- * This class defines a major component of the robot.
- *
- * A good example of a subsystem is the drivetrain, or a claw if the robot has
- * one.
- *
- * All motors should be a part of a subsystem. For instance, all the wheel
- * motors should be a part of some kind of "Drivetrain" subsystem.
- *
- * Subsystems are used within the command system as requirements for Command.
- * Only one command which requires a subsystem can run at a time. Also,
- * subsystems can have default commands which are started if there is no command
- * running which requires this subsystem.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class Subsystem : public wpi::Sendable, public wpi::SendableHelper {
- friend class Scheduler;
-
- public:
- /**
- * Creates a subsystem with the given name.
- *
- * @param name the name of the subsystem
- */
- explicit Subsystem(std::string_view name);
-
- Subsystem(Subsystem&&) = default;
- Subsystem& operator=(Subsystem&&) = default;
-
- /**
- * Sets the default command. If this is not called or is called with null,
- * then there will be no default command for the subsystem.
- *
- * WARNING: This should NOT be called in a constructor if the
- * subsystem is a singleton.
- *
- * @param command the default command (or null if there should be none)
- */
- void SetDefaultCommand(Command* command);
-
- /**
- * Returns the default command (or null if there is none).
- *
- * @return the default command
- */
- Command* GetDefaultCommand();
-
- /**
- * Returns the default command name, or empty string is there is none.
- *
- * @return the default command name
- */
- std::string GetDefaultCommandName();
-
- /**
- * Sets the current command.
- *
- * @param command the new current command
- */
- void SetCurrentCommand(Command* command);
-
- /**
- * Returns the command which currently claims this subsystem.
- *
- * @return the command which currently claims this subsystem
- */
- Command* GetCurrentCommand() const;
-
- /**
- * Returns the current command name, or empty string if no current command.
- *
- * @return the current command name
- */
- std::string GetCurrentCommandName() const;
-
- /**
- * When the run method of the scheduler is called this method will be called.
- */
- virtual void Periodic();
-
- /**
- * Initialize the default command for this subsystem.
- *
- * This is meant to be the place to call SetDefaultCommand in a subsystem and
- * will be called on all the subsystems by the CommandBase method before the
- * program starts running by using the list of all registered Subsystems
- * inside the Scheduler.
- *
- * This should be overridden by a Subsystem that has a default Command
- */
- virtual void InitDefaultCommand();
-
- /**
- * Gets the name of this Subsystem.
- *
- * @return Name
- */
- std::string GetName() const;
-
- /**
- * Sets the name of this Subsystem.
- *
- * @param name name
- */
- void SetName(std::string_view name);
-
- /**
- * Gets the subsystem name of this Subsystem.
- *
- * @return Subsystem name
- */
- std::string GetSubsystem() const;
-
- /**
- * Sets the subsystem name of this Subsystem.
- *
- * @param subsystem subsystem name
- */
- void SetSubsystem(std::string_view subsystem);
-
- /**
- * Associate a Sendable with this Subsystem.
- * Also update the child's name.
- *
- * @param name name to give child
- * @param child sendable
- */
- void AddChild(std::string_view name, std::shared_ptr child);
-
- /**
- * Associate a Sendable with this Subsystem.
- * Also update the child's name.
- *
- * @param name name to give child
- * @param child sendable
- */
- void AddChild(std::string_view name, wpi::Sendable* child);
-
- /**
- * Associate a Sendable with this Subsystem.
- * Also update the child's name.
- *
- * @param name name to give child
- * @param child sendable
- */
- void AddChild(std::string_view name, wpi::Sendable& child);
-
- /**
- * Associate a Sendable with this Subsystem.
- *
- * @param child sendable
- */
- void AddChild(std::shared_ptr child);
-
- /**
- * Associate a Sendable with this Subsystem.
- *
- * @param child sendable
- */
- void AddChild(wpi::Sendable* child);
-
- /**
- * Associate a Sendable with this Subsystem.
- *
- * @param child sendable
- */
- void AddChild(wpi::Sendable& child);
-
- private:
- /**
- * Call this to alert Subsystem that the current command is actually the
- * command.
- *
- * Sometimes, the Subsystem is told that it has no command while the Scheduler
- * is going through the loop, only to be soon after given a new one. This will
- * avoid that situation.
- */
- void ConfirmCommand();
-
- Command* m_currentCommand = nullptr;
- bool m_currentCommandChanged = true;
- Command* m_defaultCommand = nullptr;
- bool m_initializedDefaultCommand = false;
-
- public:
- void InitSendable(wpi::SendableBuilder& builder) override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h
deleted file mode 100644
index 912bcec0d0..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/TimedCommand.h
+++ /dev/null
@@ -1,69 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A TimedCommand will wait for a timeout before finishing.
- *
- * TimedCommand is used to execute a command for a given amount of time.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class TimedCommand : public Command {
- public:
- /**
- * Creates a new TimedCommand with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time before this command "times out"
- */
- TimedCommand(std::string_view name, units::second_t timeout);
-
- /**
- * Creates a new WaitCommand with the given timeout.
- *
- * @param timeout the time before this command "times out"
- */
- explicit TimedCommand(units::second_t timeout);
-
- /**
- * Creates a new TimedCommand with the given name and timeout.
- *
- * @param name the name of the command
- * @param timeout the time before this command "times out"
- * @param subsystem the subsystem that the command requires
- */
- TimedCommand(std::string_view name, units::second_t timeout,
- Subsystem& subsystem);
-
- /**
- * Creates a new WaitCommand with the given timeout.
- *
- * @param timeout the time before this command "times out"
- * @param subsystem the subsystem that the command requires
- */
- TimedCommand(units::second_t timeout, Subsystem& subsystem);
-
- ~TimedCommand() override = default;
-
- TimedCommand(TimedCommand&&) = default;
- TimedCommand& operator=(TimedCommand&&) = default;
-
- protected:
- /**
- * Ends command when timed out.
- */
- bool IsFinished() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h
deleted file mode 100644
index 9f4090b091..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/WaitCommand.h
+++ /dev/null
@@ -1,44 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-
-#include "frc/commands/TimedCommand.h"
-
-namespace frc {
-
-/**
- * A WaitCommand will wait for a certain amount of time before finishing. It is
- * useful if you want a CommandGroup to pause for a moment.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class WaitCommand : public TimedCommand {
- public:
- /**
- * Creates a new WaitCommand with the given name and timeout.
- *
- * @param timeout the time before this command "times out"
- */
- explicit WaitCommand(units::second_t timeout);
-
- /**
- * Creates a new WaitCommand with the given timeout.
- *
- * @param name the name of the command
- * @param timeout the time before this command "times out"
- */
- WaitCommand(std::string_view name, units::second_t timeout);
-
- ~WaitCommand() override = default;
-
- WaitCommand(WaitCommand&&) = default;
- WaitCommand& operator=(WaitCommand&&) = default;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h b/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h
deleted file mode 100644
index 775826bcd7..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/WaitForChildren.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * This command will only finish if whatever CommandGroup it is in has no active
- * children. If it is not a part of a CommandGroup, then it will finish
- * immediately. If it is itself an active child, then the CommandGroup will
- * never end.
- *
- * This class is useful for the situation where you want to allow anything
- * running in parallel to finish, before continuing in the main CommandGroup
- * sequence.
- *
- * This class is provided by the OldCommands VendorDep
- */
-class WaitForChildren : public Command {
- public:
- explicit WaitForChildren(units::second_t timeout);
- WaitForChildren(std::string_view name, units::second_t timeout);
- ~WaitForChildren() override = default;
-
- WaitForChildren(WaitForChildren&&) = default;
- WaitForChildren& operator=(WaitForChildren&&) = default;
-
- protected:
- bool IsFinished() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h b/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h
deleted file mode 100644
index e9a5cba336..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/commands/WaitUntilCommand.h
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include
-
-#include "frc/commands/Command.h"
-
-namespace frc {
-
-/**
- * A WaitCommand will wait until a certain match time before finishing.
- *
- * This will wait until the game clock reaches some value, then continue to
- * the next command.
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @see CommandGroup
- */
-class WaitUntilCommand : public Command {
- public:
- explicit WaitUntilCommand(units::second_t time);
-
- WaitUntilCommand(std::string_view name, units::second_t time);
-
- ~WaitUntilCommand() override = default;
-
- WaitUntilCommand(WaitUntilCommand&&) = default;
- WaitUntilCommand& operator=(WaitUntilCommand&&) = default;
-
- protected:
- /**
- * Check if we've reached the actual finish time.
- */
- bool IsFinished() override;
-
- private:
- units::second_t m_time;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h
deleted file mode 100644
index f50dbb6499..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogAccelerometer.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/AnalogAccelerometer.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogAccelerometer for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDAnalogAccelerometer : public PIDSource,
- public AnalogAccelerometer {
- using AnalogAccelerometer::AnalogAccelerometer;
-
- public:
- /**
- * Get the Acceleration for the PID Source parent.
- *
- * @return The current acceleration in Gs.
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h
deleted file mode 100644
index cfe38c58fb..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogGyro.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/AnalogGyro.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogGyro for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDAnalogGyro
- : public PIDSource,
- public AnalogGyro {
- using AnalogGyro::AnalogGyro;
-
- public:
- /**
- * Get the PIDOutput for the PIDSource base object. Can be set to return
- * angle or rate using SetPIDSourceType(). Defaults to angle.
- *
- * @return The PIDOutput (angle or rate, defaults to angle)
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h
deleted file mode 100644
index 8b71a98465..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogInput.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/AnalogInput.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogInput for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDAnalogInput
- : public PIDSource,
- public AnalogInput {
- using AnalogInput::AnalogInput;
-
- public:
- /**
- * Get the Average value for the PID Source base object.
- *
- * @return The average voltage.
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h
deleted file mode 100644
index 110144e61b..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDAnalogPotentiometer.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/AnalogPotentiometer.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for AnalogPotentiometer for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.")
- PIDAnalogPotentiometer : public PIDSource,
- public AnalogPotentiometer {
- using AnalogPotentiometer::AnalogPotentiometer;
-
- public:
- /**
- * Implement the PIDSource interface.
- *
- * @return The current reading.
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h
deleted file mode 100644
index 9866f81c01..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDEncoder.h
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/Encoder.h"
-#include "frc/PIDSource.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for Encoder for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDEncoder
- : public PIDSource,
- public Encoder {
- using Encoder::Encoder;
-
- public:
- /**
- * Get the PIDOutput for the PIDSource base object. Can be set to return
- * distance or rate using SetPIDSourceType(). Defaults to distance.
- *
- * @return The PIDOutput (distance or rate, defaults to distance)
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h
deleted file mode 100644
index 4e2e0e6185..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDMotorController.h
+++ /dev/null
@@ -1,70 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-#include
-
-#include "frc/PIDOutput.h"
-#include "frc/motorcontrol/MotorController.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDOutput is implemented for MotorController for old
- * PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class PIDMotorController : public PIDOutput,
- public MotorController,
- public wpi::Sendable {
- public:
- WPI_DEPRECATED("Use frc2::PIDController class instead.")
- explicit PIDMotorController(MotorController& motorController);
-
- /**
- * Set the PWM value.
- *
- * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
- * the value for the FPGA.
- *
- * @param value The speed value between -1.0 and 1.0 to set.
- */
- void Set(double value) override;
-
- /**
- * Get the recently set value of the PWM. This value is affected by the
- * inversion property. If you want the value that is sent directly to the
- * MotorController, use PWM::GetSpeed() instead.
- *
- * @return The most recently set value for the PWM between -1.0 and 1.0.
- */
- double Get() const override;
-
- void SetInverted(bool isInverted) override;
-
- bool GetInverted() const override;
-
- void Disable() override;
-
- void StopMotor() override;
-
- void PIDWrite(double output) override;
-
- protected:
- void InitSendable(wpi::SendableBuilder& builder) override;
-
- private:
- bool m_isInverted = false;
-
- MotorController& m_motorController;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h b/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h
deleted file mode 100644
index 0742f544d0..0000000000
--- a/wpilibOldCommands/src/main/native/include/frc/pidwrappers/PIDUltrasonic.h
+++ /dev/null
@@ -1,36 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-#include "frc/PIDSource.h"
-#include "frc/Ultrasonic.h"
-
-namespace frc {
-
-/**
- * Wrapper so that PIDSource is implemented for Ultrasonic for old PIDController
- *
- * This class is provided by the OldCommands VendorDep
- *
- * @deprecated Use frc2::PIDController class instead which doesn't require this
- * wrapper.
- */
-class WPI_DEPRECATED("Use frc2::PIDController class instead.") PIDUltrasonic
- : public PIDSource,
- public Ultrasonic {
- using Ultrasonic::Ultrasonic;
-
- public:
- /**
- * Get the range for the PIDSource base object.
- *
- * @return The range
- */
- double PIDGet() override;
-};
-
-} // namespace frc
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
deleted file mode 100644
index e70f182a3b..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
+++ /dev/null
@@ -1,38 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj;
-
-import edu.wpi.first.hal.HAL;
-import edu.wpi.first.wpilibj.simulation.DriverStationSim;
-import org.junit.jupiter.api.extension.BeforeAllCallback;
-import org.junit.jupiter.api.extension.ExtensionContext;
-import org.junit.jupiter.api.extension.ExtensionContext.Namespace;
-
-public final class MockHardwareExtension implements BeforeAllCallback {
- private static ExtensionContext getRoot(ExtensionContext context) {
- return context.getParent().map(MockHardwareExtension::getRoot).orElse(context);
- }
-
- @Override
- public void beforeAll(ExtensionContext context) {
- getRoot(context)
- .getStore(Namespace.GLOBAL)
- .getOrComputeIfAbsent(
- "HAL Initialized",
- key -> {
- initializeHardware();
- return true;
- },
- Boolean.class);
- }
-
- private void initializeHardware() {
- HAL.initialize(500, 0);
- DriverStationSim.setDsAttached(true);
- DriverStationSim.setAutonomous(false);
- DriverStationSim.setEnabled(true);
- DriverStationSim.setTest(true);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
deleted file mode 100644
index 55411cc425..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
+++ /dev/null
@@ -1,49 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static org.junit.jupiter.api.Assertions.assertAll;
-import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
-import static org.junit.jupiter.api.Assertions.assertEquals;
-
-import org.junit.jupiter.api.BeforeEach;
-
-/** The basic test for all {@link Command} tests. */
-public class AbstractCommandTest {
- @BeforeEach
- void commandSetup() {
- Scheduler.getInstance().removeAll();
- Scheduler.getInstance().enable();
- }
-
- public static class ASubsystem extends Subsystem {
- Command m_command;
-
- @Override
- protected void initDefaultCommand() {
- if (m_command != null) {
- setDefaultCommand(m_command);
- }
- }
-
- public void init(Command command) {
- m_command = command;
- }
- }
-
- protected void assertCommandState(
- MockCommand command, int initialize, int execute, int isFinished, int end, int interrupted) {
- assertAll(
- () -> assertEquals(initialize, command.getInitializeCount()),
- () -> assertEquals(execute, command.getExecuteCount()),
- () -> assertEquals(isFinished, command.getIsFinishedCount()),
- () -> assertEquals(end, command.getEndCount()),
- () -> assertEquals(interrupted, command.getInterruptedCount()));
- }
-
- protected void sleep(int time) {
- assertDoesNotThrow(() -> Thread.sleep(time));
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
deleted file mode 100644
index 0569268a47..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
+++ /dev/null
@@ -1,108 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import edu.wpi.first.wpilibj.buttons.InternalButton;
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-/**
- * Test that covers the {@link edu.wpi.first.wpilibj.buttons.Button} with the {@link Command}
- * library.
- */
-class ButtonTest extends AbstractCommandTest {
- private InternalButton m_button1;
- private InternalButton m_button2;
-
- @BeforeEach
- void setUp() {
- m_button1 = new InternalButton();
- m_button2 = new InternalButton();
- }
-
- /** Simple Button Test. */
- @Test
- void buttonTest() {
- final MockCommand command1 = new MockCommand();
- final MockCommand command2 = new MockCommand();
- final MockCommand command3 = new MockCommand();
- final MockCommand command4 = new MockCommand();
-
- m_button1.whenPressed(command1);
- m_button1.whenReleased(command2);
- m_button1.whileHeld(command3);
- m_button2.whileHeld(command4);
-
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- m_button1.setPressed(true);
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 1, 1, 1, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 2, 2, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 1, 2, 2, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- m_button2.setPressed(true);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 1, 3, 3, 0, 0);
- assertCommandState(command4, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 1, 4, 4, 0, 0);
- assertCommandState(command4, 1, 1, 1, 0, 0);
- m_button1.setPressed(false);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 5, 5, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 6, 6, 0, 0);
- assertCommandState(command2, 1, 1, 1, 0, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 3, 3, 0, 0);
- m_button2.setPressed(false);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 7, 7, 0, 0);
- assertCommandState(command2, 1, 2, 2, 0, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 3, 3, 0, 1);
- command1.cancel();
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 7, 7, 0, 1);
- assertCommandState(command2, 1, 3, 3, 0, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 3, 3, 0, 1);
- command2.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 7, 7, 0, 1);
- assertCommandState(command2, 1, 4, 4, 1, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 3, 3, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 7, 7, 0, 1);
- assertCommandState(command2, 1, 4, 4, 1, 0);
- assertCommandState(command3, 1, 4, 4, 0, 1);
- assertCommandState(command4, 1, 3, 3, 0, 1);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
deleted file mode 100644
index 04a920cc3b..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
+++ /dev/null
@@ -1,48 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandParallelGroupTest extends AbstractCommandTest {
- /** Simple Parallel Command Group With 2 commands one command terminates first. */
- @Test
- void parallelCommandGroupWithTwoCommandsTest() {
- final MockCommand command1 = new MockCommand();
- final MockCommand command2 = new MockCommand();
-
- try (CommandGroup commandGroup = new CommandGroup()) {
- commandGroup.addParallel(command1);
- commandGroup.addParallel(command2);
-
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- commandGroup.start();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 0);
- assertCommandState(command2, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 2, 2, 0, 0);
- assertCommandState(command2, 1, 2, 2, 0, 0);
- command1.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 1, 0);
- assertCommandState(command2, 1, 3, 3, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 1, 0);
- assertCommandState(command2, 1, 4, 4, 0, 0);
- command2.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 1, 0);
- assertCommandState(command2, 1, 5, 5, 1, 0);
- }
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
deleted file mode 100644
index 5592045fa4..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
+++ /dev/null
@@ -1,54 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandScheduleTest extends AbstractCommandTest {
- /**
- * Simple scheduling of a command and making sure the command is run and successfully terminates.
- */
- @Test
- void runAndTerminateTest() {
- final MockCommand command = new MockCommand();
- command.start();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 2, 2, 0, 0);
- command.setHasFinished(true);
- assertCommandState(command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 1, 0);
- }
-
- /** Simple scheduling of a command and making sure the command is run and cancels correctly. */
- @Test
- void runAndCancelTest() {
- final MockCommand command = new MockCommand();
- command.start();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 0, 0);
- command.cancel();
- assertCommandState(command, 1, 3, 3, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 0, 1);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
deleted file mode 100644
index d8ef9337db..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
+++ /dev/null
@@ -1,86 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import java.util.logging.Logger;
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandSequentialGroupTest extends AbstractCommandTest {
- private static final Logger logger = Logger.getLogger(CommandSequentialGroupTest.class.getName());
-
- /**
- * Simple Command Group With 3 commands that all depend on a subsystem. Some commands have a
- * timeout.
- */
- @Test
- void testThreeCommandOnSubSystem() {
- logger.fine("Beginning Test");
- final ASubsystem subsystem = new ASubsystem();
-
- logger.finest("Creating Mock Command1");
- final MockCommand command1 = new MockCommand(subsystem);
- logger.finest("Creating Mock Command2");
- final MockCommand command2 = new MockCommand(subsystem);
- logger.finest("Creating Mock Command3");
- final MockCommand command3 = new MockCommand(subsystem);
-
- logger.finest("Creating Command Group");
- try (CommandGroup commandGroup = new CommandGroup()) {
- commandGroup.addSequential(command1, 1.0);
- commandGroup.addSequential(command2, 2.0);
- commandGroup.addSequential(command3);
-
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- logger.finest("Starting Command group");
- commandGroup.start();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- sleep(1250); // command 1 timeout
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 1, 1, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
-
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 0);
- assertCommandState(command3, 0, 0, 0, 0, 0);
- sleep(2500); // command 2 timeout
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 1);
- assertCommandState(command3, 1, 1, 1, 0, 0);
-
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 1);
- assertCommandState(command3, 1, 2, 2, 0, 0);
- command3.setHasFinished(true);
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 1);
- assertCommandState(command3, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 1);
- assertCommandState(command3, 1, 3, 3, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 1);
- assertCommandState(command3, 1, 3, 3, 1, 0);
- }
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
deleted file mode 100644
index 7169c39f45..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
+++ /dev/null
@@ -1,92 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Ported from the old CrioTest Classes. */
-class CommandSupersedeTest extends AbstractCommandTest {
- /** Testing one command superseding another because of dependencies. */
- @Test
- void oneCommandSupersedingAnotherBecauseOfDependenciesTest() {
- final ASubsystem subsystem = new ASubsystem();
-
- final MockCommand command1 = new MockCommand(subsystem);
-
- final MockCommand command2 = new MockCommand(subsystem);
-
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- command1.start();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 2, 2, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- command2.start();
- assertCommandState(command1, 1, 3, 3, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 1);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 1);
- assertCommandState(command2, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 1);
- assertCommandState(command2, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 1);
- assertCommandState(command2, 1, 3, 3, 0, 0);
- }
-
- /**
- * Testing one command failing superseding another because of dependencies because the first
- * command cannot be interrupted.
- */
- @Test
- @SuppressWarnings("PMD.NonStaticInitializer")
- void commandFailingSupersedingBecauseFirstCanNotBeInterruptedTest() {
- final ASubsystem subsystem = new ASubsystem();
-
- final MockCommand command1 = new MockCommand(subsystem);
- command1.setInterruptible(false);
-
- final MockCommand command2 = new MockCommand(subsystem);
-
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- command1.start();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 0, 0, 0, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 1, 1, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 2, 2, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 3, 3, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- command2.start();
- assertCommandState(command1, 1, 3, 3, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command1, 1, 4, 4, 0, 0);
- assertCommandState(command2, 0, 0, 0, 0, 0);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
deleted file mode 100644
index 069e0990be..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Test a {@link Command} that times out. */
-class CommandTimeoutTest extends AbstractCommandTest {
- /** Command 2 second Timeout Test. */
- @Test
- void twoSecondTimeoutTest() {
- final ASubsystem subsystem = new ASubsystem();
-
- final MockCommand command =
- new MockCommand(subsystem, 2) {
- @Override
- public boolean isFinished() {
- return super.isFinished() || isTimedOut();
- }
- };
-
- command.start();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 3, 3, 0, 0);
- sleep(2500);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 4, 4, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(command, 1, 4, 4, 1, 0);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
deleted file mode 100644
index 97d33774d0..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
+++ /dev/null
@@ -1,345 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertSame;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-class ConditionalCommandTest extends AbstractCommandTest {
- MockConditionalCommand m_command;
- MockConditionalCommand m_commandNull;
- MockCommand m_onTrue;
- MockCommand m_onFalse;
- MockSubsystem m_subsys;
-
- @BeforeEach
- void initCommands() {
- m_subsys = new MockSubsystem();
- m_onTrue = new MockCommand(m_subsys);
- m_onFalse = new MockCommand(m_subsys);
- m_command = new MockConditionalCommand(m_onTrue, m_onFalse);
- m_commandNull = new MockConditionalCommand(m_onTrue, null);
- }
-
- protected void assertConditionalCommandState(
- MockConditionalCommand command,
- int initialize,
- int execute,
- int isFinished,
- int end,
- int interrupted) {
- assertEquals(initialize, command.getInitializeCount());
- assertEquals(execute, command.getExecuteCount());
- assertEquals(isFinished, command.getIsFinishedCount());
- assertEquals(end, command.getEndCount());
- assertEquals(interrupted, command.getInterruptedCount());
- }
-
- @Test
- void onTrueTest() {
- m_command.setCondition(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onTrue.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
- assertTrue(m_onTrue.getInitializeCount() > 0, "Did not initialize the true command");
- assertSame(m_onFalse.getInitializeCount(), 0, "Initialized the false command");
- }
-
- @Test
- void onFalseTest() {
- m_command.setCondition(false);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onFalse
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onFalse
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onFalse, 1, 2, 2, 0, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onFalse.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
- assertTrue(m_onFalse.getInitializeCount() > 0, "Did not initialize the false command");
- assertSame(m_onTrue.getInitializeCount(), 0, "Initialized the true command");
- }
-
- @Test
- void cancelSubCommandTest() {
- m_command.setCondition(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onTrue.cancel();
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
- }
-
- @Test
- void cancelRequiresTest() {
- m_command.setCondition(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onFalse.start();
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 0, 1);
- assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
- }
-
- @Test
- void cancelCondCommandTest() {
- m_command.setCondition(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_command.cancel();
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
- }
-
- @Test
- void onTrueTwiceTest() {
- m_command.setCondition(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onTrue.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
-
- m_onTrue.resetCounters();
- m_command.resetCounters();
- m_command.setCondition(true);
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
- m_onTrue.setHasFinished(true);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
- }
-
- @Test
- void onTrueInstantTest() {
- m_command.setCondition(true);
- m_onTrue.setHasFinished(true);
-
- Scheduler.getInstance().add(m_command);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onTrue
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
- assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
- }
-
- @Test
- void onFalseNullTest() {
- m_commandNull.setCondition(false);
-
- Scheduler.getInstance().add(m_commandNull);
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init command and select m_onFalse
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run(); // init m_onFalse
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
- assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
deleted file mode 100644
index 8539d44755..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
+++ /dev/null
@@ -1,99 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-import org.junit.jupiter.api.Test;
-
-/** Tests the {@link Command} library. */
-class DefaultCommandTest extends AbstractCommandTest {
- /** Testing of default commands where the interrupting command ends itself. */
- @Test
- void defaultCommandWhereTheInteruptingCommandEndsItselfTest() {
- final ASubsystem subsystem = new ASubsystem();
-
- final MockCommand defaultCommand = new MockCommand(subsystem);
-
- final MockCommand anotherCommand = new MockCommand(subsystem);
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- subsystem.init(defaultCommand);
-
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-
- anotherCommand.start();
- assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
- assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
- anotherCommand.setHasFinished(true);
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
- assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
- assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
- }
-
- /** Testing of default commands where the interrupting command is canceled. */
- @Test
- void defaultCommandsInterruptingCommandCanceledTest() {
- final ASubsystem subsystem = new ASubsystem();
- final MockCommand defaultCommand = new MockCommand(subsystem);
- final MockCommand anotherCommand = new MockCommand(subsystem);
-
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- subsystem.init(defaultCommand);
- subsystem.initDefaultCommand();
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
-
- anotherCommand.start();
- assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
- assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
- anotherCommand.cancel();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
- Scheduler.getInstance().run();
- assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
- assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
deleted file mode 100644
index 5d1715be43..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
+++ /dev/null
@@ -1,126 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/**
- * A class to simulate a simple command. The command keeps track of how many times each method was
- * called.
- */
-public class MockCommand extends Command {
- private int m_initializeCount;
- private int m_executeCount;
- private int m_isFinishedCount;
- private boolean m_hasFinished;
- private int m_endCount;
- private int m_interruptedCount;
-
- public MockCommand(Subsystem subsys) {
- super();
- requires(subsys);
- }
-
- public MockCommand(Subsystem subsys, double timeout) {
- this(subsys);
- setTimeout(timeout);
- }
-
- public MockCommand() {
- super();
- }
-
- @Override
- protected void initialize() {
- ++m_initializeCount;
- }
-
- @Override
- protected void execute() {
- ++m_executeCount;
- }
-
- @Override
- protected boolean isFinished() {
- ++m_isFinishedCount;
- return isHasFinished();
- }
-
- @Override
- protected void end() {
- ++m_endCount;
- }
-
- @Override
- protected void interrupted() {
- ++m_interruptedCount;
- }
-
- /** How many times the initialize method has been called. */
- public int getInitializeCount() {
- return m_initializeCount;
- }
-
- /** If the initialize method has been called at least once. */
- public boolean hasInitialized() {
- return getInitializeCount() > 0;
- }
-
- /** How many time the execute method has been called. */
- public int getExecuteCount() {
- return m_executeCount;
- }
-
- /** How many times the isFinished method has been called. */
- public int getIsFinishedCount() {
- return m_isFinishedCount;
- }
-
- /**
- * Get what value the isFinished method will return.
- *
- * @return what value the isFinished method will return.
- */
- public boolean isHasFinished() {
- return m_hasFinished;
- }
-
- /**
- * Set what value the isFinished method will return.
- *
- * @param hasFinished set what value the isFinished method will return.
- */
- public void setHasFinished(boolean hasFinished) {
- m_hasFinished = hasFinished;
- }
-
- /** How many times the end method has been called. */
- public int getEndCount() {
- return m_endCount;
- }
-
- /** If the end method has been called at least once. */
- public boolean hasEnd() {
- return getEndCount() > 0;
- }
-
- /** How many times the interrupted method has been called. */
- public int getInterruptedCount() {
- return m_interruptedCount;
- }
-
- /** If the interrupted method has been called at least once. */
- public boolean hasInterrupted() {
- return getInterruptedCount() > 0;
- }
-
- /** Reset internal counters. */
- public void resetCounters() {
- m_initializeCount = 0;
- m_executeCount = 0;
- m_isFinishedCount = 0;
- m_hasFinished = false;
- m_endCount = 0;
- m_interruptedCount = 0;
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
deleted file mode 100644
index 8ac2aee9f7..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
+++ /dev/null
@@ -1,103 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-public class MockConditionalCommand extends ConditionalCommand {
- private boolean m_condition;
- private int m_initializeCount;
- private int m_executeCount;
- private int m_isFinishedCount;
- private int m_endCount;
- private int m_interruptedCount;
-
- public MockConditionalCommand(MockCommand onTrue, MockCommand onFalse) {
- super(onTrue, onFalse);
- }
-
- @Override
- protected boolean condition() {
- return m_condition;
- }
-
- public void setCondition(boolean condition) {
- this.m_condition = condition;
- }
-
- @Override
- protected void initialize() {
- ++m_initializeCount;
- }
-
- @Override
- protected void execute() {
- ++m_executeCount;
- }
-
- @Override
- protected boolean isFinished() {
- ++m_isFinishedCount;
- return super.isFinished();
- }
-
- @Override
- protected void end() {
- ++m_endCount;
- }
-
- @Override
- protected void interrupted() {
- ++m_interruptedCount;
- }
-
- /** How many times the initialize method has been called. */
- public int getInitializeCount() {
- return m_initializeCount;
- }
-
- /** If the initialize method has been called at least once. */
- public boolean hasInitialized() {
- return getInitializeCount() > 0;
- }
-
- /** How many time the execute method has been called. */
- public int getExecuteCount() {
- return m_executeCount;
- }
-
- /** How many times the isFinished method has been called. */
- public int getIsFinishedCount() {
- return m_isFinishedCount;
- }
-
- /** How many times the end method has been called. */
- public int getEndCount() {
- return m_endCount;
- }
-
- /** If the end method has been called at least once. */
- public boolean hasEnd() {
- return getEndCount() > 0;
- }
-
- /** How many times the interrupted method has been called. */
- public int getInterruptedCount() {
- return m_interruptedCount;
- }
-
- /** If the interrupted method has been called at least once. */
- public boolean hasInterrupted() {
- return getInterruptedCount() > 0;
- }
-
- /** Reset internal counters. */
- public void resetCounters() {
- m_condition = false;
- m_initializeCount = 0;
- m_executeCount = 0;
- m_isFinishedCount = 0;
- m_endCount = 0;
- m_interruptedCount = 0;
- }
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
deleted file mode 100644
index e2b1bf778c..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.command;
-
-/** A class to simulate a simple subsystem. */
-public class MockSubsystem extends Subsystem {
- @Override
- protected void initDefaultCommand() {}
-}
diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
deleted file mode 100644
index c7deb235f6..0000000000
--- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
+++ /dev/null
@@ -1,146 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.shuffleboard;
-
-import static org.junit.jupiter.api.Assertions.assertAll;
-import static org.junit.jupiter.api.Assertions.assertArrayEquals;
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertFalse;
-import static org.junit.jupiter.api.Assertions.assertThrows;
-
-import edu.wpi.first.networktables.NetworkTableEntry;
-import edu.wpi.first.networktables.NetworkTableInstance;
-import edu.wpi.first.util.sendable.Sendable;
-import edu.wpi.first.wpilibj.command.InstantCommand;
-import java.util.HashMap;
-import java.util.Map;
-import org.junit.jupiter.api.AfterEach;
-import org.junit.jupiter.api.BeforeEach;
-import org.junit.jupiter.api.Test;
-
-class ShuffleboardTabTest {
- private NetworkTableInstance m_ntInstance;
- private ShuffleboardTab m_tab;
- private ShuffleboardInstance m_instance;
-
- @BeforeEach
- void setup() {
- m_ntInstance = NetworkTableInstance.create();
- m_instance = new ShuffleboardInstance(m_ntInstance);
- m_tab = m_instance.getTab("Tab");
- }
-
- @AfterEach
- void tearDown() {
- m_ntInstance.close();
- }
-
- @Test
- void testAddDouble() {
- NetworkTableEntry entry = m_tab.add("Double", 1.0).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/Double", entry.getName()),
- () -> assertEquals(1.0, entry.getValue().getDouble()));
- }
-
- @Test
- void testAddInteger() {
- NetworkTableEntry entry = m_tab.add("Int", 1).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/Int", entry.getName()),
- () -> assertEquals(1.0, entry.getValue().getDouble()));
- }
-
- @Test
- void testAddLong() {
- NetworkTableEntry entry = m_tab.add("Long", 1L).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/Long", entry.getName()),
- () -> assertEquals(1.0, entry.getValue().getDouble()));
- }
-
- @Test
- void testAddBoolean() {
- NetworkTableEntry entry = m_tab.add("Bool", false).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/Bool", entry.getName()),
- () -> assertFalse(entry.getValue().getBoolean()));
- }
-
- @Test
- void testAddString() {
- NetworkTableEntry entry = m_tab.add("String", "foobar").getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/String", entry.getName()),
- () -> assertEquals("foobar", entry.getValue().getString()));
- }
-
- @Test
- void testAddNamedSendableWithProperties() {
- Sendable sendable = new InstantCommand("Command");
- String widgetType = "Command Widget";
- m_tab.add(sendable).withWidget(widgetType).withProperties(mapOf("foo", 1234, "bar", "baz"));
-
- m_instance.update();
- String meta = "/Shuffleboard/.metadata/Tab/Command";
-
- assertAll(
- () ->
- assertEquals(
- 1234,
- m_ntInstance.getEntry(meta + "/Properties/foo").getDouble(-1),
- "Property 'foo' not set correctly"),
- () ->
- assertEquals(
- "baz",
- m_ntInstance.getEntry(meta + "/Properties/bar").getString(null),
- "Property 'bar' not set correctly"),
- () ->
- assertEquals(
- widgetType,
- m_ntInstance.getEntry(meta + "/PreferredComponent").getString(null),
- "Preferred component not set correctly"));
- }
-
- @Test
- void testAddNumberArray() {
- NetworkTableEntry entry = m_tab.add("DoubleArray", new double[] {1, 2, 3}).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/DoubleArray", entry.getName()),
- () -> assertArrayEquals(new double[] {1, 2, 3}, entry.getValue().getDoubleArray()));
- }
-
- @Test
- void testAddBooleanArray() {
- NetworkTableEntry entry = m_tab.add("BoolArray", new boolean[] {true, false}).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/BoolArray", entry.getName()),
- () -> assertArrayEquals(new boolean[] {true, false}, entry.getValue().getBooleanArray()));
- }
-
- @Test
- void testAddStringArray() {
- NetworkTableEntry entry = m_tab.add("StringArray", new String[] {"foo", "bar"}).getEntry();
- assertAll(
- () -> assertEquals("/Shuffleboard/Tab/StringArray", entry.getName()),
- () -> assertArrayEquals(new String[] {"foo", "bar"}, entry.getValue().getStringArray()));
- }
-
- @Test
- void testTitleDuplicates() {
- m_tab.add("foo", "bar");
- assertThrows(IllegalArgumentException.class, () -> m_tab.add("foo", "baz"));
- }
-
- /** Stub for Java 9 {@code Map.of()}. */
- @SuppressWarnings("unchecked")
- private static Map mapOf(Object... entries) {
- Map map = new HashMap<>();
- for (int i = 0; i < entries.length; i += 2) {
- map.put((K) entries[i], (V) entries[i + 1]);
- }
- return map;
- }
-}
diff --git a/wpilibOldCommands/src/test/native/cpp/main.cpp b/wpilibOldCommands/src/test/native/cpp/main.cpp
deleted file mode 100644
index 6aea19a01e..0000000000
--- a/wpilibOldCommands/src/test/native/cpp/main.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include
-
-#include "gtest/gtest.h"
-
-int main(int argc, char** argv) {
- HAL_Initialize(500, 0);
- ::testing::InitGoogleTest(&argc, argv);
- int ret = RUN_ALL_TESTS();
- return ret;
-}
diff --git a/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp b/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
deleted file mode 100644
index 4cbad010f9..0000000000
--- a/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
+++ /dev/null
@@ -1,111 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include
-#include
-#include
-
-#include
-#include
-
-#include "frc/commands/InstantCommand.h"
-#include "frc/shuffleboard/ShuffleboardInstance.h"
-#include "frc/shuffleboard/ShuffleboardTab.h"
-#include "gtest/gtest.h"
-
-using namespace frc;
-
-class ShuffleboardTabTest : public testing::Test {
- void SetUp() override {
- m_ntInstance = nt::NetworkTableInstance::Create();
- m_instance = std::make_unique(m_ntInstance);
- m_tab = &(m_instance->GetTab("Tab"));
- }
-
- protected:
- nt::NetworkTableInstance m_ntInstance;
- ShuffleboardTab* m_tab;
- std::unique_ptr m_instance;
-};
-
-TEST_F(ShuffleboardTabTest, AddDouble) {
- auto entry = m_tab->Add("Double", 1.0).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/Double", entry.GetName());
- EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
-}
-
-TEST_F(ShuffleboardTabTest, AddInteger) {
- auto entry = m_tab->Add("Int", 1).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/Int", entry.GetName());
- EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
-}
-
-TEST_F(ShuffleboardTabTest, AddBoolean) {
- auto entry = m_tab->Add("Bool", false).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/Bool", entry.GetName());
- EXPECT_FALSE(entry.GetValue()->GetBoolean());
-}
-
-TEST_F(ShuffleboardTabTest, AddString) {
- auto entry = m_tab->Add("String", "foobar").GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/String", entry.GetName());
- EXPECT_EQ("foobar", entry.GetValue()->GetString());
-}
-
-TEST_F(ShuffleboardTabTest, AddNamedSendableWithProperties) {
- InstantCommand sendable("Command");
- std::string widgetType = "Command Widget";
- wpi::StringMap> map;
- map.try_emplace("foo", nt::Value::MakeDouble(1234));
- map.try_emplace("bar", nt::Value::MakeString("baz"));
- m_tab->Add(sendable).WithWidget(widgetType).WithProperties(map);
-
- m_instance->Update();
- std::string meta = "/Shuffleboard/.metadata/Tab/Command";
-
- EXPECT_EQ(1234, m_ntInstance.GetEntry(meta + "/Properties/foo").GetDouble(-1))
- << "Property 'foo' not set correctly";
- EXPECT_EQ("baz",
- m_ntInstance.GetEntry(meta + "/Properties/bar").GetString(""))
- << "Property 'bar' not set correctly";
- EXPECT_EQ(widgetType,
- m_ntInstance.GetEntry(meta + "/PreferredComponent").GetString(""))
- << "Preferred component not set correctly";
-}
-
-TEST_F(ShuffleboardTabTest, AddNumberArray) {
- std::array expect = {{1.0, 2.0, 3.0}};
- auto entry = m_tab->Add("DoubleArray", expect).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/DoubleArray", entry.GetName());
-
- auto actual = entry.GetValue()->GetDoubleArray();
- EXPECT_EQ(expect.size(), actual.size());
- for (size_t i = 0; i < expect.size(); i++) {
- EXPECT_FLOAT_EQ(expect[i], actual[i]);
- }
-}
-
-TEST_F(ShuffleboardTabTest, AddBooleanArray) {
- std::array expect = {{true, false}};
- auto entry = m_tab->Add("BoolArray", expect).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/BoolArray", entry.GetName());
-
- auto actual = entry.GetValue()->GetBooleanArray();
- EXPECT_EQ(expect.size(), actual.size());
- for (size_t i = 0; i < expect.size(); i++) {
- EXPECT_EQ(expect[i], actual[i]);
- }
-}
-
-TEST_F(ShuffleboardTabTest, AddStringArray) {
- std::array expect = {{"foo", "bar"}};
- auto entry = m_tab->Add("StringArray", expect).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/StringArray", entry.GetName());
-
- auto actual = entry.GetValue()->GetStringArray();
- EXPECT_EQ(expect.size(), actual.size());
- for (size_t i = 0; i < expect.size(); i++) {
- EXPECT_EQ(expect[i], actual[i]);
- }
-}
diff --git a/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp b/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
deleted file mode 100644
index 94603300ea..0000000000
--- a/wpilibOldCommands/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
+++ /dev/null
@@ -1,61 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include
-#include
-#include
-
-#include
-#include
-
-#include "frc/commands/InstantCommand.h"
-#include "frc/shuffleboard/BuiltInWidgets.h"
-#include "frc/shuffleboard/ShuffleboardInstance.h"
-#include "frc/shuffleboard/ShuffleboardTab.h"
-#include "frc/shuffleboard/ShuffleboardWidget.h"
-#include "gtest/gtest.h"
-
-using namespace frc;
-
-class ShuffleboardWidgetTest : public testing::Test {
- void SetUp() override {
- m_ntInstance = nt::NetworkTableInstance::Create();
- m_instance = std::make_unique(m_ntInstance);
- m_tab = &(m_instance->GetTab("Tab"));
- }
-
- protected:
- nt::NetworkTableInstance m_ntInstance;
- ShuffleboardTab* m_tab;
- std::unique_ptr m_instance;
-};
-
-TEST_F(ShuffleboardWidgetTest, UseBuiltInWidget) {
- auto entry =
- m_tab->Add("Name", "").WithWidget(BuiltInWidgets::kTextView).GetEntry();
- EXPECT_EQ("/Shuffleboard/Tab/Name", entry.GetName())
- << "The widget entry has the wrong name";
-}
-
-TEST_F(ShuffleboardWidgetTest, WithProperties) {
- wpi::StringMap> properties{
- std::make_pair("min", nt::Value::MakeDouble(0)),
- std::make_pair("max", nt::Value::MakeDouble(1))};
- auto entry =
- m_tab->Add("WithProperties", "").WithProperties(properties).GetEntry();
-
- // Update the instance to generate
- // the metadata entries for the widget properties
- m_instance->Update();
-
- auto propertiesTable = m_ntInstance.GetTable(
- "/Shuffleboard/.metadata/Tab/WithProperties/Properties");
-
- EXPECT_EQ("/Shuffleboard/Tab/WithProperties", entry.GetName())
- << "The widget entry has the wrong name";
- EXPECT_FLOAT_EQ(0, propertiesTable->GetEntry("min").GetDouble(-1))
- << "The 'min' property should be 0";
- EXPECT_FLOAT_EQ(1, propertiesTable->GetEntry("max").GetDouble(-1))
- << "The 'max' property should be 1";
-}
diff --git a/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension b/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
deleted file mode 100644
index 981f17041a..0000000000
--- a/wpilibOldCommands/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
+++ /dev/null
@@ -1 +0,0 @@
-edu.wpi.first.wpilibj.MockHardwareExtension
diff --git a/wpilibOldCommands/wpilibOldCommands-config.cmake.in b/wpilibOldCommands/wpilibOldCommands-config.cmake.in
deleted file mode 100644
index 81dde79519..0000000000
--- a/wpilibOldCommands/wpilibOldCommands-config.cmake.in
+++ /dev/null
@@ -1,11 +0,0 @@
-include(CMakeFindDependencyMacro)
-@FILENAME_DEP_REPLACE@
-@WPIUTIL_DEP_REPLACE@
-@NTCORE_DEP_REPLACE@
-@CSCORE_DEP_REPLACE@
-@CAMERASERVER_DEP_REPLACE@
-@HAL_DEP_REPLACE@
-@WPILIBC_DEP_REPLACE@
-@WPIMATH_DEP_REPLACE@
-
-include(${SELF_DIR}/wpilibOldCommands.cmake)
diff --git a/wpilibcExamples/CMakeLists.txt b/wpilibcExamples/CMakeLists.txt
index 27cff6b4d7..f8c637f831 100644
--- a/wpilibcExamples/CMakeLists.txt
+++ b/wpilibcExamples/CMakeLists.txt
@@ -11,7 +11,7 @@ foreach(example ${EXAMPLES})
src/main/cpp/examples/${example}/c/*.c)
add_executable(${example} ${sources})
target_include_directories(${example} PUBLIC src/main/cpp/examples/${example}/include)
- target_link_libraries(${example} wpilibc wpilibNewCommands wpilibOldCommands)
+ target_link_libraries(${example} wpilibc wpilibNewCommands)
if (WITH_TESTS AND EXISTS ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/test/cpp/examples/${example})
wpilib_add_test(${example} src/test/cpp/examples/${example}/cpp)
diff --git a/wpilibcExamples/build.gradle b/wpilibcExamples/build.gradle
index 7561ed5e53..50f06d1772 100644
--- a/wpilibcExamples/build.gradle
+++ b/wpilibcExamples/build.gradle
@@ -64,7 +64,6 @@ model {
binary.buildable = false
return
}
- lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'shared'
lib project: ':wpilibNewCommands', library: 'wpilibNewCommands', linkage: 'shared'
lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
diff --git a/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp b/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
deleted file mode 100644
index 24726b013c..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeCommand.h"
-
-ReplaceMeCommand::ReplaceMeCommand() {
- // Use Requires() here to declare subsystem dependencies
- // eg. Requires(Robot::chassis.get());
-}
-
-// Called just before this Command runs the first time
-void ReplaceMeCommand::Initialize() {}
-
-// Called repeatedly when this Command is scheduled to run
-void ReplaceMeCommand::Execute() {}
-
-// Make this return true when this Command no longer needs to run execute()
-bool ReplaceMeCommand::IsFinished() {
- return false;
-}
-
-// Called once after isFinished returns true
-void ReplaceMeCommand::End() {}
-
-// Called when another command which requires one or more of the same
-// subsystems is scheduled to run
-void ReplaceMeCommand::Interrupted() {}
diff --git a/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h b/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
deleted file mode 100644
index 64fcd26a16..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMeCommand : public frc::Command {
- public:
- ReplaceMeCommand();
- void Initialize() override;
- void Execute() override;
- bool IsFinished() override;
- void End() override;
- void Interrupted() override;
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp b/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
deleted file mode 100644
index ced938d688..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeCommandGroup.h"
-
-ReplaceMeCommandGroup::ReplaceMeCommandGroup() {
- // Add Commands here:
- // e.g. AddSequential(new Command1());
- // AddSequential(new Command2());
- // these will run in order.
-
- // To run multiple commands at the same time,
- // use AddParallel()
- // e.g. AddParallel(new Command1());
- // AddSequential(new Command2());
- // Command1 and Command2 will run in parallel.
-
- // A command group will require all of the subsystems that each member
- // would require.
- // e.g. if Command1 requires chassis, and Command2 requires arm,
- // a CommandGroup containing them would require both the chassis and the
- // arm.
-}
diff --git a/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h b/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
deleted file mode 100644
index c51a96408b..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
+++ /dev/null
@@ -1,12 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMeCommandGroup : public frc::CommandGroup {
- public:
- ReplaceMeCommandGroup();
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/commands.json b/wpilibcExamples/src/main/cpp/commands/commands.json
index 6b5bf1ec7a..7f0c8f9a15 100644
--- a/wpilibcExamples/src/main/cpp/commands/commands.json
+++ b/wpilibcExamples/src/main/cpp/commands/commands.json
@@ -16,120 +16,7 @@
"commandversion": 0
},
{
- "name": "Command (Old)",
- "description": "Create a base command",
- "tags": [
- "command"
- ],
- "foldername": "command",
- "headers": [
- "ReplaceMeCommand.h"
- ],
- "source": [
- "ReplaceMeCommand.cpp"
- ],
- "replacename": "ReplaceMeCommand",
- "commandversion": 1
- },
- {
- "name": "Command Group (Old)",
- "description": "Create a command group",
- "tags": [
- "commandgroup"
- ],
- "foldername": "commandgroup",
- "headers": [
- "ReplaceMeCommandGroup.h"
- ],
- "source": [
- "ReplaceMeCommandGroup.cpp"
- ],
- "replacename": "ReplaceMeCommandGroup",
- "commandversion": 1
- },
- {
- "name": "Instant Command (Old)",
- "description": "A command that runs immediately",
- "tags": [
- "instantcommand"
- ],
- "foldername": "instant",
- "headers": [
- "ReplaceMeInstantCommand.h"
- ],
- "source": [
- "ReplaceMeInstantCommand.cpp"
- ],
- "replacename": "ReplaceMeInstantCommand",
- "commandversion": 1
- },
- {
- "name": "Subsystem (Old)",
- "description": "A subsystem",
- "tags": [
- "subsystem"
- ],
- "foldername": "subsystem",
- "headers": [
- "ReplaceMeSubsystem.h"
- ],
- "source": [
- "ReplaceMeSubsystem.cpp"
- ],
- "replacename": "ReplaceMeSubsystem",
- "commandversion": 1
- },
- {
- "name": "PID Subsystem (Old)",
- "description": "A subsystem that runs a PID loop",
- "tags": [
- "pidsubsystem",
- "pid"
- ],
- "foldername": "pidsubsystem",
- "headers": [
- "ReplaceMePIDSubsystem.h"
- ],
- "source": [
- "ReplaceMePIDSubsystem.cpp"
- ],
- "replacename": "ReplaceMePIDSubsystem",
- "commandversion": 1
- },
- {
- "name": "Timed Command (Old)",
- "description": "A command that runs for a specified time",
- "tags": [
- "timedcommand"
- ],
- "foldername": "timed",
- "headers": [
- "ReplaceMeTimedCommand.h"
- ],
- "source": [
- "ReplaceMeTimedCommand.cpp"
- ],
- "replacename": "ReplaceMeTimedCommand",
- "commandversion": 1
- },
- {
- "name": "Trigger (Old)",
- "description": "A command that runs off of a trigger",
- "tags": [
- "trigger"
- ],
- "foldername": "trigger",
- "headers": [
- "ReplaceMeTrigger.h"
- ],
- "source": [
- "ReplaceMeTrigger.cpp"
- ],
- "replacename": "ReplaceMeTrigger",
- "commandversion": 1
- },
- {
- "name": "Command (New)",
+ "name": "Command",
"description": "A command.",
"tags": [
"command"
@@ -145,7 +32,7 @@
"commandversion": 2
},
{
- "name": "InstantCommand (New)",
+ "name": "InstantCommand",
"description": "A command that finishes instantly.",
"tags": [
"instantcommand"
@@ -161,7 +48,7 @@
"commandversion": 2
},
{
- "name": "ParallelCommandGroup (New)",
+ "name": "ParallelCommandGroup",
"description": "A command group that runs commands in parallel, ending when all commands have finished.",
"tags": [
"parallelcommandgroup"
@@ -177,7 +64,7 @@
"commandversion": 2
},
{
- "name": "ParallelDeadlineGroup (New)",
+ "name": "ParallelDeadlineGroup",
"description": "A command group that runs commands in parallel, ending when a specific command has finished.",
"tags": [
"paralleldeadlinegroup"
@@ -193,7 +80,7 @@
"commandversion": 2
},
{
- "name": "ParallelRaceGroup (New)",
+ "name": "ParallelRaceGroup",
"description": "A command that runs commands in parallel, ending as soon as any command has finished.",
"tags": [
"parallelracegroup"
@@ -209,7 +96,7 @@
"commandversion": 2
},
{
- "name": "PIDCommand (New)",
+ "name": "PIDCommand",
"description": "A command that runs a PIDController.",
"tags": [
"pidcommand"
@@ -225,7 +112,7 @@
"commandversion": 2
},
{
- "name": "PIDSubsystem (New)",
+ "name": "PIDSubsystem",
"description": "A subsystem that runs a PIDController.",
"tags": [
"pidsubsystem"
@@ -241,7 +128,7 @@
"commandversion": 2
},
{
- "name": "ProfiledPIDCommand (New)",
+ "name": "ProfiledPIDCommand",
"description": "A command that runs a ProfiledPIDController.",
"tags": [
"profiledpidcommand"
@@ -257,7 +144,7 @@
"commandversion": 2
},
{
- "name": "ProfiledPIDSubsystem (New)",
+ "name": "ProfiledPIDSubsystem",
"description": "A subsystem that runs a ProfiledPIDController.",
"tags": [
"profiledpidsubsystem"
@@ -273,7 +160,7 @@
"commandversion": 2
},
{
- "name": "SequentialCommandGroup (New)",
+ "name": "SequentialCommandGroup",
"description": "A command group that runs commands in sequence.",
"tags": [
"sequentialcommandgroup"
@@ -289,7 +176,7 @@
"commandversion": 2
},
{
- "name": "Subsystem (New)",
+ "name": "Subsystem",
"description": "A robot subsystem.",
"tags": [
"subsystem"
@@ -305,7 +192,7 @@
"commandversion": 2
},
{
- "name": "TrapezoidProfileCommand (New)",
+ "name": "TrapezoidProfileCommand",
"description": "A command that executes a trapezoidal motion profile.",
"tags": [
"trapezoidprofilecommand"
@@ -321,7 +208,7 @@
"commandversion": 2
},
{
- "name": "TrapezoidProfileSubsystem (New)",
+ "name": "TrapezoidProfileSubsystem",
"description": "A subsystem that executes a trapezoidal motion profile.",
"tags": [
"trapezoidprofilesubsystem"
diff --git a/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp b/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
deleted file mode 100644
index 1a802885a7..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeInstantCommand.h"
-
-ReplaceMeInstantCommand::ReplaceMeInstantCommand() {
- // Use Requires() here to declare subsystem dependencies
- // eg. Requires(Robot::chassis.get());
-}
-
-// Called once when the command executes
-void ReplaceMeInstantCommand::Initialize() {}
diff --git a/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h b/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
deleted file mode 100644
index c73cbcfa9c..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMeInstantCommand : public frc::InstantCommand {
- public:
- ReplaceMeInstantCommand();
- void Initialize() override;
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp b/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
deleted file mode 100644
index 7b44893f48..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMePIDSubsystem.h"
-
-#include
-#include
-
-ReplaceMePIDSubsystem::ReplaceMePIDSubsystem()
- : PIDSubsystem("ReplaceMePIDSubsystem", 1.0, 0.0, 0.0) {
- // Use these to get going:
- // SetSetpoint() - Sets where the PID controller should move the system
- // to
- // Enable() - Enables the PID controller.
-}
-
-double ReplaceMePIDSubsystem::ReturnPIDInput() {
- // Return your input value for the PID loop
- // e.g. a sensor, like a potentiometer:
- // yourPot->SetAverageVoltage() / kYourMaxVoltage;
- return 0;
-}
-
-void ReplaceMePIDSubsystem::UsePIDOutput(double output) {
- // Use output to drive your system, like a motor
- // e.g. yourMotor->Set(output);
-}
-
-void ReplaceMePIDSubsystem::InitDefaultCommand() {
- // Set the default command for a subsystem here.
- // SetDefaultCommand(new MySpecialCommand());
-}
diff --git a/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h b/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
deleted file mode 100644
index f9aabc9b3b..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMePIDSubsystem : public frc::PIDSubsystem {
- public:
- ReplaceMePIDSubsystem();
- double ReturnPIDInput() override;
- void UsePIDOutput(double output) override;
- void InitDefaultCommand() override;
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp b/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
deleted file mode 100644
index ca589f18b8..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeSubsystem.h"
-
-ReplaceMeSubsystem::ReplaceMeSubsystem() : Subsystem("ExampleSubsystem") {}
-
-void ReplaceMeSubsystem::InitDefaultCommand() {
- // Set the default command for a subsystem here.
- // SetDefaultCommand(new MySpecialCommand());
-}
-
-// Put methods for controlling this subsystem
-// here. Call these from Commands.
diff --git a/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h b/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
deleted file mode 100644
index 3de6031ded..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMeSubsystem : public frc::Subsystem {
- private:
- // It's desirable that everything possible under private except
- // for methods that implement subsystem capabilities
-
- public:
- ReplaceMeSubsystem();
- void InitDefaultCommand() override;
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp b/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
deleted file mode 100644
index c6793e04da..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeTimedCommand.h"
-
-ReplaceMeTimedCommand::ReplaceMeTimedCommand(units::second_t timeout)
- : TimedCommand(timeout) {
- // Use Requires() here to declare subsystem dependencies
- // eg. Requires(Robot::chassis.get());
-}
-
-// Called just before this Command runs the first time
-void ReplaceMeTimedCommand::Initialize() {}
-
-// Called repeatedly when this Command is scheduled to run
-void ReplaceMeTimedCommand::Execute() {}
-
-// Called once after command times out
-void ReplaceMeTimedCommand::End() {}
-
-// Called when another command which requires one or more of the same
-// subsystems is scheduled to run
-void ReplaceMeTimedCommand::Interrupted() {}
diff --git a/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h b/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
deleted file mode 100644
index 48cfa2d5b9..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
+++ /dev/null
@@ -1,17 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-#include
-
-class ReplaceMeTimedCommand : public frc::TimedCommand {
- public:
- explicit ReplaceMeTimedCommand(units::second_t timeout);
- void Initialize() override;
- void Execute() override;
- void End() override;
- void Interrupted() override;
-};
diff --git a/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp b/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
deleted file mode 100644
index 3c563ffeb8..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#include "ReplaceMeTrigger.h"
-
-ReplaceMeTrigger::ReplaceMeTrigger() = default;
-
-bool ReplaceMeTrigger::Get() {
- return false;
-}
diff --git a/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h b/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
deleted file mode 100644
index a76dcd99d8..0000000000
--- a/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
+++ /dev/null
@@ -1,13 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-#pragma once
-
-#include
-
-class ReplaceMeTrigger : public frc::Trigger {
- public:
- ReplaceMeTrigger();
- bool Get() override;
-};
diff --git a/wpilibcIntegrationTests/build.gradle b/wpilibcIntegrationTests/build.gradle
index 4d66667439..dbfda457e3 100644
--- a/wpilibcIntegrationTests/build.gradle
+++ b/wpilibcIntegrationTests/build.gradle
@@ -44,7 +44,6 @@ model {
cppCompiler.args "-Wno-unused-variable"
cppCompiler.args "-Wno-error=deprecated-declarations"
}
- lib project: ':wpilibOldCommands', library: 'wpilibOldCommands', linkage: 'shared'
lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
lib project: ':wpimath', library: 'wpimath', linkage: 'shared'
lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
index 8df2c46b45..5f1074e98f 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
@@ -284,9 +284,8 @@ public enum BuiltInWidgets implements WidgetType {
* Supported types:
*
*
- * - {@link edu.wpi.first.wpilibj.command.Command}
- *
- {@link edu.wpi.first.wpilibj.command.CommandGroup}
- *
- Any custom subclass of {@code Command} or {@code CommandGroup}
+ *
- {@link edu.wpi.first.wpilibj2.command.Command}
+ *
- Any custom subclass of {@code Command}
*
*
*
@@ -300,7 +299,7 @@ public enum BuiltInWidgets implements WidgetType {
* Supported types:
*
*
- * - {@link edu.wpi.first.wpilibj.command.PIDCommand}
+ *
- {@link edu.wpi.first.wpilibj2.command.PIDCommand}
*
- Any custom subclass of {@code PIDCommand}
*
*
@@ -314,7 +313,7 @@ public enum BuiltInWidgets implements WidgetType {
* Supported types:
*
*
- * - {@link edu.wpi.first.wpilibj.PIDController}
+ *
- {@link edu.wpi.first.math.controller.PIDController}
*
*
*
diff --git a/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle
index 7d74e80ab0..12a38e80e6 100644
--- a/wpilibjExamples/build.gradle
+++ b/wpilibjExamples/build.gradle
@@ -34,7 +34,6 @@ dependencies {
implementation project(':ntcore')
implementation project(':cscore')
implementation project(':cameraserver')
- implementation project(':wpilibOldCommands')
implementation project(':wpilibNewCommands')
testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2'
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
deleted file mode 100644
index 5ca1ca1288..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
+++ /dev/null
@@ -1,37 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.command;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-public class ReplaceMeCommand extends Command {
- public ReplaceMeCommand() {
- // Use requires() here to declare subsystem dependencies
- // eg. requires(chassis);
- }
-
- // Called just before this Command runs the first time
- @Override
- protected void initialize() {}
-
- // Called repeatedly when this Command is scheduled to run
- @Override
- protected void execute() {}
-
- // Make this return true when this Command no longer needs to run execute()
- @Override
- protected boolean isFinished() {
- return false;
- }
-
- // Called once after isFinished returns true
- @Override
- protected void end() {}
-
- // Called when another command which requires one or more of the same
- // subsystems is scheduled to run
- @Override
- protected void interrupted() {}
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
deleted file mode 100644
index ba8e273022..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.commandgroup;
-
-import edu.wpi.first.wpilibj.command.CommandGroup;
-
-public class ReplaceMeCommandGroup extends CommandGroup {
- /** Add your docs here. */
- public ReplaceMeCommandGroup() {
- // Add Commands here:
- // e.g. addSequential(new Command1());
- // addSequential(new Command2());
- // these will run in order.
-
- // To run multiple commands at the same time,
- // use addParallel()
- // e.g. addParallel(new Command1());
- // addSequential(new Command2());
- // Command1 and Command2 will run in parallel.
-
- // A command group will require all of the subsystems that each member
- // would require.
- // e.g. if Command1 requires chassis, and Command2 requires arm,
- // a CommandGroup containing them would require both the chassis and the
- // arm.
- }
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
index 8165a3c237..f6f2c374a9 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
@@ -10,78 +10,7 @@
"commandversion": 0
},
{
- "name": "Command (Old)",
- "description": "Create a base command",
- "tags": [
- "command"
- ],
- "foldername": "command",
- "replacename": "ReplaceMeCommand",
- "commandversion": 1
- },
- {
- "name": "Command Group (Old)",
- "description": "Create a command group",
- "tags": [
- "commandgroup"
- ],
- "foldername": "commandgroup",
- "replacename": "ReplaceMeCommandGroup",
- "commandversion": 1
- },
- {
- "name": "Instant Command (Old)",
- "description": "A command that runs immediately",
- "tags": [
- "instantcommand"
- ],
- "foldername": "instant",
- "replacename": "ReplaceMeInstantCommand",
- "commandversion": 1
- },
- {
- "name": "Subsystem (Old)",
- "description": "A subsystem",
- "tags": [
- "subsystem"
- ],
- "foldername": "subsystem",
- "replacename": "ReplaceMeSubsystem",
- "commandversion": 1
- },
- {
- "name": "PID Subsystem (Old)",
- "description": "A subsystem that runs a PID loop",
- "tags": [
- "pidsubsystem",
- "pid"
- ],
- "foldername": "pidsubsystem",
- "replacename": "ReplaceMePIDSubsystem",
- "commandversion": 1
- },
- {
- "name": "Timed Command (Old)",
- "description": "A command that runs for a specified time",
- "tags": [
- "timedcommand"
- ],
- "foldername": "timed",
- "replacename": "ReplaceMeTimedCommand",
- "commandversion": 1
- },
- {
- "name": "Trigger (Old)",
- "description": "A command that runs off of a trigger",
- "tags": [
- "trigger"
- ],
- "foldername": "trigger",
- "replacename": "ReplaceMeTrigger",
- "commandversion": 1
- },
- {
- "name": "Command (New)",
+ "name": "Command",
"description": "A command.",
"tags": [
"command"
@@ -91,7 +20,7 @@
"commandversion": 2
},
{
- "name": "InstantCommand (New)",
+ "name": "InstantCommand",
"description": "A command that finishes instantly.",
"tags": [
"instantcommand"
@@ -101,7 +30,7 @@
"commandversion": 2
},
{
- "name": "ParallelCommandGroup (New)",
+ "name": "ParallelCommandGroup",
"description": "A command group that runs commands in parallel, ending when all commands have finished.",
"tags": [
"parallelcommandgroup"
@@ -111,7 +40,7 @@
"commandversion": 2
},
{
- "name": "ParallelDeadlineGroup (New)",
+ "name": "ParallelDeadlineGroup",
"description": "A command group that runs commands in parallel, ending when a specific command has finished.",
"tags": [
"paralleldeadlinegroup"
@@ -121,7 +50,7 @@
"commandversion": 2
},
{
- "name": "ParallelRaceGroup (New)",
+ "name": "ParallelRaceGroup",
"description": "A command that runs commands in parallel, ending as soon as any command has finished.",
"tags": [
"parallelracegroup"
@@ -131,7 +60,7 @@
"commandversion": 2
},
{
- "name": "PIDCommand (New)",
+ "name": "PIDCommand",
"description": "A command that runs a PIDController.",
"tags": [
"pidcommand"
@@ -141,7 +70,7 @@
"commandversion": 2
},
{
- "name": "PIDSubsystem (New)",
+ "name": "PIDSubsystem",
"description": "A subsystem that runs a PIDController.",
"tags": [
"pidsubsystem"
@@ -151,7 +80,7 @@
"commandversion": 2
},
{
- "name": "ProfiledPIDCommand (New)",
+ "name": "ProfiledPIDCommand",
"description": "A command that runs a ProfiledPIDController.",
"tags": [
"profiledpidcommand"
@@ -161,7 +90,7 @@
"commandversion": 2
},
{
- "name": "ProfiledPIDSubsystem (New)",
+ "name": "ProfiledPIDSubsystem",
"description": "A subsystem that runs a ProfiledPIDController.",
"tags": [
"profiledpidsubsystem"
@@ -171,7 +100,7 @@
"commandversion": 2
},
{
- "name": "SequentialCommandGroup (New)",
+ "name": "SequentialCommandGroup",
"description": "A command group that runs commands in sequence.",
"tags": [
"sequentialcommandgroup"
@@ -181,7 +110,7 @@
"commandversion": 2
},
{
- "name": "Subsystem (New)",
+ "name": "Subsystem",
"description": "A robot subsystem.",
"tags": [
"subsystem"
@@ -191,7 +120,7 @@
"commandversion": 2
},
{
- "name": "TrapezoidProfileCommand (New)",
+ "name": "TrapezoidProfileCommand",
"description": "A command that executes a trapezoidal motion profile.",
"tags": [
"trapezoidprofilecommand"
@@ -201,7 +130,7 @@
"commandversion": 2
},
{
- "name": "TrapezoidProfileSubsystem (New)",
+ "name": "TrapezoidProfileSubsystem",
"description": "A subystem that executes a trapezoidal motion profile.",
"tags": [
"trapezoidprofilesubsystem"
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
deleted file mode 100644
index 769b595b9c..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
+++ /dev/null
@@ -1,21 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.instant;
-
-import edu.wpi.first.wpilibj.command.InstantCommand;
-
-/** Add your docs here. */
-public class ReplaceMeInstantCommand extends InstantCommand {
- /** Add your docs here. */
- public ReplaceMeInstantCommand() {
- super();
- // Use requires() here to declare subsystem dependencies
- // eg. requires(chassis);
- }
-
- // Called once when the command executes
- @Override
- protected void initialize() {}
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
deleted file mode 100644
index 01e798729f..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.pidsubsystem;
-
-import edu.wpi.first.wpilibj.command.PIDSubsystem;
-
-/** Add your docs here. */
-public class ReplaceMePIDSubsystem extends PIDSubsystem {
- /** Add your docs here. */
- public ReplaceMePIDSubsystem() {
- // Intert a subsystem name and PID values here
- super("SubsystemName", 1, 2, 3);
- // Use these to get going:
- // setSetpoint() - Sets where the PID controller should move the system
- // to
- // enable() - Enables the PID controller.
- }
-
- @Override
- public void initDefaultCommand() {
- // Set the default command for a subsystem here.
- // setDefaultCommand(new MySpecialCommand());
- }
-
- @Override
- protected double returnPIDInput() {
- // Return your input value for the PID loop
- // e.g. a sensor, like a potentiometer:
- // yourPot.getAverageVoltage() / kYourMaxVoltage;
- return 0.0;
- }
-
- @Override
- protected void usePIDOutput(double output) {
- // Use output to drive your system, like a motor
- // e.g. yourMotor.set(output);
- }
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
deleted file mode 100644
index 671daf15fe..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
+++ /dev/null
@@ -1,19 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.subsystem;
-
-import edu.wpi.first.wpilibj.command.Subsystem;
-
-/** Add your docs here. */
-public class ReplaceMeSubsystem extends Subsystem {
- // Put methods for controlling this subsystem
- // here. Call these from Commands.
-
- @Override
- public void initDefaultCommand() {
- // Set the default command for a subsystem here.
- // setDefaultCommand(new MySpecialCommand());
- }
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
deleted file mode 100644
index 6021382ac1..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.timed;
-
-import edu.wpi.first.wpilibj.command.TimedCommand;
-
-/** Add your docs here. */
-public class ReplaceMeTimedCommand extends TimedCommand {
- /** Add your docs here. */
- public ReplaceMeTimedCommand(double timeout) {
- super(timeout);
- // Use requires() here to declare subsystem dependencies
- // eg. requires(chassis);
- }
-
- // Called just before this Command runs the first time
- @Override
- protected void initialize() {}
-
- // Called repeatedly when this Command is scheduled to run
- @Override
- protected void execute() {}
-
- // Called once after timeout
- @Override
- protected void end() {}
-
- // Called when another command which requires one or more of the same
- // subsystems is scheduled to run
- @Override
- protected void interrupted() {}
-}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
deleted file mode 100644
index c1343d93e2..0000000000
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
+++ /dev/null
@@ -1,15 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj.commands.trigger;
-
-import edu.wpi.first.wpilibj.buttons.Trigger;
-
-/** Add your docs here. */
-public class ReplaceMeTrigger extends Trigger {
- @Override
- public boolean get() {
- return false;
- }
-}