diff --git a/subsystems/OverridableSubsystem.java b/subsystems/OverridableSubsystem.java
index 3075f532..3c9a9cea 100644
--- a/subsystems/OverridableSubsystem.java
+++ b/subsystems/OverridableSubsystem.java
@@ -3,6 +3,7 @@
import org.usfirst.frc4904.standard.custom.Overridable;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
+// TO DO: extend RequirementsSubsystemBase instead
public abstract class OverridableSubsystem extends SubsystemBase implements Overridable {
private boolean isOverridden = false;
diff --git a/subsystems/RequirementsSubsystemBase.java b/subsystems/RequirementsSubsystemBase.java
new file mode 100644
index 00000000..4fe2eccc
--- /dev/null
+++ b/subsystems/RequirementsSubsystemBase.java
@@ -0,0 +1,103 @@
+package org.usfirst.frc4904.standard.subsystems;
+
+import java.util.Arrays;
+import java.util.List;
+import java.util.stream.Stream;
+
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandBase;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
+import edu.wpi.first.wpilibj2.command.Subsystem;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+
+// TO DO: extend RequirementsSubsystemBase instead
+// TO DO: custom trigger that takes a command factory
+// TO DO: parallel command group that doesn't require it's own subsystems
+public class RequirementsSubsystemBase extends SubsystemBase {
+ public final RequirementsSubsystemBase[] atomicComponents;
+
+ /**
+ * SubsystemBase that handles requirements better.
+ *
+ * Most subsystems should pass `this` only, or each internal subsystem. See below for details.
+ *
+ *
+ *
+ * On 4904, we sometimes use subsystems containing other subsystems
+ * (composition).
+ *
+ * This confuses requirements. Say P composes A and B. Parallel commands on P
+ * (that use both A and B) should not require both P AND A and B, because
+ * otherwise a new command that just means to take over A will inadvertantly
+ * cancel P which will cancel the action on B.
+ *
+ *
+ * Therefore,
+ * - if your internal subsystems should never be controlled seprately from one another, (eg. left and right drive motors of a chassis), just pass `this` to group them together.
+ * - if your internal subsystems may be controlled seprately, (eg. a pivot+extension arm subsystem where one degree of freedom may be held while the other is manipulated), pass both `ArmPivotSubsystem` and `ArmExtensionSubsystem` but not `this`
+ *
+ * @param atomicSubsystemRequirements
+ */
+ public RequirementsSubsystemBase(RequirementsSubsystemBase... atomicSubsystemRequirements) {
+ atomicComponents = Arrays.stream(atomicSubsystemRequirements)
+ .flatMap((rsb) -> Arrays.stream(rsb.atomicComponents))
+ .toArray(RequirementsSubsystemBase[]::new);
+ }
+
+ /**
+ * Constructs a command that runs an action once and finishes. Requires this
+ * subsystem.
+ *
+ * @param action the action to run
+ * @return the command
+ * @see InstantCommand
+ */
+ public CommandBase runOnce(Runnable action) {
+ return Commands.runOnce(action, atomicComponents);
+ }
+
+ /**
+ * Constructs a command that runs an action every iteration until interrupted.
+ * Requires this
+ * subsystem.
+ *
+ * @param action the action to run
+ * @return the command
+ * @see RunCommand
+ */
+ public CommandBase run(Runnable action) {
+ return Commands.run(action, atomicComponents);
+ }
+
+ /**
+ * Constructs a command that runs an action once and another action when the
+ * command is
+ * interrupted. Requires this subsystem.
+ *
+ * @param start the action to run on start
+ * @param end the action to run on interrupt
+ * @return the command
+ * @see StartEndCommand
+ */
+ public CommandBase startEnd(Runnable start, Runnable end) {
+ return Commands.startEnd(start, end, atomicComponents);
+ }
+
+ /**
+ * Constructs a command that runs an action every iteration until interrupted,
+ * and then runs a
+ * second action. Requires this subsystem.
+ *
+ * @param run the action to run every iteration
+ * @param end the action to run on interrupt
+ * @return the command
+ */
+ public CommandBase runEnd(Runnable run, Runnable end) {
+ return Commands.runEnd(run, end, atomicComponents);
+ }
+
+ public CommandBase parallel(Command... commands) {
+ return new ParallelCommandGroup(commands); // do not require the atomic components, so that if one subcommand gets cancelled, the other one does not.
+ }
+}
diff --git a/subsystems/SolenoidSubsystem.java b/subsystems/SolenoidSubsystem.java
index 382bdf08..b96a95ee 100644
--- a/subsystems/SolenoidSubsystem.java
+++ b/subsystems/SolenoidSubsystem.java
@@ -9,6 +9,7 @@
* functionality. Allows for easy inversion and setting of default state of
* solenoids
*/
+// TO DO: extend RequirementsSubsystemBase instead
public class SolenoidSubsystem extends SubsystemBase {
protected DoubleSolenoid[] solenoids;
protected SolenoidState state;
diff --git a/subsystems/chassis/WestCoastDrive.java b/subsystems/chassis/WestCoastDrive.java
index 10286f4c..a537556b 100644
--- a/subsystems/chassis/WestCoastDrive.java
+++ b/subsystems/chassis/WestCoastDrive.java
@@ -5,6 +5,7 @@
import java.util.function.Supplier;
import org.usfirst.frc4904.robot.RobotMap;
+import org.usfirst.frc4904.standard.subsystems.RequirementsSubsystemBase;
import org.usfirst.frc4904.standard.subsystems.motor.TalonMotorSubsystem;
import com.kauailabs.navx.frc.AHRS;
@@ -28,9 +29,8 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
-import edu.wpi.first.wpilibj2.command.SubsystemBase;
-public class WestCoastDrive extends SubsystemBase {
+public class WestCoastDrive extends RequirementsSubsystemBase {
public final TalonMotorSubsystem leftMotors;
public final TalonMotorSubsystem rightMotors;
protected final PIDConstants pidConsts;
diff --git a/subsystems/motor/ServoSubsystem.java b/subsystems/motor/ServoSubsystem.java
index 5d9323b4..ff4c953e 100644
--- a/subsystems/motor/ServoSubsystem.java
+++ b/subsystems/motor/ServoSubsystem.java
@@ -4,6 +4,7 @@
import edu.wpi.first.wpilibj.Servo;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
+// TO DO: extend RequirementsSubsystemBase instead
public class ServoSubsystem extends SubsystemBase {
protected final Servo[] servos;
protected boolean isInverted;
diff --git a/subsystems/motor/SmartMotorSubsystem.java b/subsystems/motor/SmartMotorSubsystem.java
index fe800aba..5578de4a 100644
--- a/subsystems/motor/SmartMotorSubsystem.java
+++ b/subsystems/motor/SmartMotorSubsystem.java
@@ -3,16 +3,16 @@
import java.util.function.DoubleSupplier;
import org.usfirst.frc4904.standard.custom.motorcontrollers.SmartMotorController;
+import org.usfirst.frc4904.standard.subsystems.RequirementsSubsystemBase;
import org.usfirst.frc4904.standard.subsystems.motor.speedmodifiers.IdentityModifier;
import org.usfirst.frc4904.standard.subsystems.motor.speedmodifiers.SpeedModifier;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandBase;
-import edu.wpi.first.wpilibj2.command.SubsystemBase;
-public abstract class SmartMotorSubsystem extends SubsystemBase { // generic to allow inherited class (eg. TalonMotorSubsystem) to directly use TalonMotorController APIs on super.motors (not possible if this.motors here was BrakeableMotorController)
+public abstract class SmartMotorSubsystem extends RequirementsSubsystemBase { // generic to allow inherited class (eg. TalonMotorSubsystem) to directly use TalonMotorController APIs on super.motors (not possible if this.motors here was BrakeableMotorController)
public static final int DEFAULT_PID_SLOT = 0; // default slot for pid constants
public static final int DEFAULT_DMP_SLOT = 0; // default slot for dynamic motion profile (motionmagic or smartmotion) configuration
diff --git a/subsystems/motor/speedmodifiers/EnableableModifier.java b/subsystems/motor/speedmodifiers/EnableableModifier.java
index 3c344981..813a6f8b 100644
--- a/subsystems/motor/speedmodifiers/EnableableModifier.java
+++ b/subsystems/motor/speedmodifiers/EnableableModifier.java
@@ -6,6 +6,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
+@Deprecated
public class EnableableModifier extends SubsystemBase implements SpeedModifier {
protected boolean enabled;
protected final SpeedModifier modifier;
diff --git a/subsystems/net/UDPSocket.java b/subsystems/net/UDPSocket.java
index 21659151..42802a92 100644
--- a/subsystems/net/UDPSocket.java
+++ b/subsystems/net/UDPSocket.java
@@ -10,12 +10,12 @@
import org.msgpack.core.MessageUnpacker;
import org.msgpack.core.buffer.ByteBufferInput;
import org.msgpack.core.buffer.MessageBuffer;
+import org.usfirst.frc4904.standard.subsystems.RequirementsSubsystemBase;
// import org.usfirst.frc4904.standard.LogKitten;
import org.usfirst.frc4904.standard.subsystems.net.message.Packable;
-import edu.wpi.first.wpilibj2.command.SubsystemBase;
-public abstract class UDPSocket extends SubsystemBase {
+public abstract class UDPSocket extends RequirementsSubsystemBase {
private static final int RECV_BUFFER_SIZE = 1024;
private DatagramChannel channel;