From e1fd7c9cbc70162afa16fed141237e2620e7af3f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:13:05 -0400 Subject: [PATCH 001/153] Add commandsv3 subproject --- commandsv3/CMakeLists.txt | 60 ++++++++++++++++++++ commandsv3/CommandsV3.json | 18 ++++++ commandsv3/build.gradle | 50 ++++++++++++++++ commandsv3/wpilibnewcommands-config.cmake.in | 14 +++++ settings.gradle | 1 + 5 files changed, 143 insertions(+) create mode 100644 commandsv3/CMakeLists.txt create mode 100644 commandsv3/CommandsV3.json create mode 100644 commandsv3/build.gradle create mode 100644 commandsv3/wpilibnewcommands-config.cmake.in diff --git a/commandsv3/CMakeLists.txt b/commandsv3/CMakeLists.txt new file mode 100644 index 00000000000..4c9fe0f950a --- /dev/null +++ b/commandsv3/CMakeLists.txt @@ -0,0 +1,60 @@ +project(commandsv3) + +include(SubDirList) +include(CompileWarnings) +include(AddTest) + +if(WITH_JAVA) + find_package(Java REQUIRED) + include(UseJava) + set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked") + + file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) + add_jar( + commandsv3_jar + ${JAVA_SOURCES} + INCLUDE_JARS + hal_jar + ntcore_jar + cscore_jar + cameraserver_jar + wpimath_jar + wpiunits_jar + wpiutil_jar + wpilibj_jar + OUTPUT_NAME commandsv3 + ) + + install_jar(commandsv3_jar DESTINATION ${java_lib_dest}) + install_jar_exports( + TARGETS commandsv3_jar + FILE commandsv3_jar.cmake + DESTINATION share/commandsv3 + ) +endif() + +if(WITH_JAVA_SOURCE) + find_package(Java REQUIRED) + include(UseJava) + file(GLOB commandsv3_SOURCES src/main/java/edu/wpi/first/wpilibj/commandsv3/*.java) + file(GLOB commandsv3_BUTTON_SOURCES src/main/java/edu/wpi/first/wpilibj2/command/button*.java) + add_jar( + commandsv3_src_jar + RESOURCES + NAMESPACE "edu/wpi/first/wpilibj/commandsv3" ${commandsv3_SOURCES} + NAMESPACE "edu/wpi/first/wpilibj/commandsv3/button" ${commandsv3_BUTTON_SOURCES} + OUTPUT_NAME commandsv3-sources + ) + + get_property(commandsv3_SRC_JAR_FILE TARGET commandsv3_src_jar PROPERTY JAR_FILE) + install(FILES ${commandsv3_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") + + set_property(TARGET commandsv3_src_jar PROPERTY FOLDER "java") +endif() + +install(TARGETS commandsv3 EXPORT commandsv3) +export(TARGETS commandsv3 FILE commandsv3.cmake NAMESPACE commandsv3::) + +configure_file(commandsv3-config.cmake.in ${WPILIB_BINARY_DIR}/commandsv3-config.cmake) +install(FILES ${WPILIB_BINARY_DIR}/commandsv3-config.cmake DESTINATION share/commandsv3) +install(EXPORT commandsv3 DESTINATION share/commandsv3) diff --git a/commandsv3/CommandsV3.json b/commandsv3/CommandsV3.json new file mode 100644 index 00000000000..015f7296a7c --- /dev/null +++ b/commandsv3/CommandsV3.json @@ -0,0 +1,18 @@ +{ + "fileName": "CommandsV3.json", + "name": "Commands v3", + "version": "1.0.0", + "uuid": "4decdc05-a056-46cf-9561-39449bbb0130", + "frcYear": "2024", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.commandsv3", + "artifactId": "commandsv3-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [] +} diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle new file mode 100644 index 00000000000..d6fb4d0537d --- /dev/null +++ b/commandsv3/build.gradle @@ -0,0 +1,50 @@ +ext { + useJava = true + useCpp = false + baseId = 'commandsv3' + groupId = 'edu.wpi.first.wpilibj' + + nativeName = 'commandsv3' + devMain = '' +} + +apply from: "${rootDir}/shared/java/javacommon.gradle" + +evaluationDependsOn(':wpiutil') +evaluationDependsOn(':ntcore') +evaluationDependsOn(':hal') +evaluationDependsOn(':wpimath') +evaluationDependsOn(':wpilibj') + +dependencies { + implementation project(':wpiutil') + implementation project(':wpinet') + implementation project(':ntcore') + implementation project(':hal') + implementation project(':wpimath') + implementation project(':wpilibj') + api("us.hebi.quickbuf:quickbuf-runtime:1.3.3") + testImplementation 'org.mockito:mockito-core:4.1.0' +} + +sourceSets.main.resources.srcDir "${projectDir}/src/main/proto" + +tasks.withType(Javadoc) { + options.addBooleanOption("-enable-preview", true) + options.addStringOption("-release", "21") +} + +test { + testLogging { + outputs.upToDateWhen {false} + showStandardStreams = true + } + doFirst { + jvmArgs = [ + '--add-opens', + 'java.base/jdk.internal.vm=ALL-UNNAMED', + '--add-opens', + 'java.base/java.lang=ALL-UNNAMED', + ] + } +} diff --git a/commandsv3/wpilibnewcommands-config.cmake.in b/commandsv3/wpilibnewcommands-config.cmake.in new file mode 100644 index 00000000000..b26b9a7a555 --- /dev/null +++ b/commandsv3/wpilibnewcommands-config.cmake.in @@ -0,0 +1,14 @@ +include(CMakeFindDependencyMacro) +@WPIUTIL_DEP_REPLACE@ +@NTCORE_DEP_REPLACE@ +@CSCORE_DEP_REPLACE@ +@CAMERASERVER_DEP_REPLACE@ +@HAL_DEP_REPLACE@ +@WPILIBC_DEP_REPLACE@ +@WPIMATH_DEP_REPLACE@ + +@FILENAME_DEP_REPLACE@ +include(${SELF_DIR}/wpilibnewcommands.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/wpilibNewCommands_jar.cmake) +endif() diff --git a/settings.gradle b/settings.gradle index 0461327371c..a3be2a0bf8f 100644 --- a/settings.gradle +++ b/settings.gradle @@ -46,6 +46,7 @@ include 'simulation:halsim_xrp' include 'cameraserver' include 'cameraserver:multiCameraServer' include 'wpilibNewCommands' +include 'commandsv3' include 'romiVendordep' include 'xrpVendordep' include 'developerRobot' From 0dcaaaf1a6938b3befc3831a3e240f2747dd9232 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:13:53 -0400 Subject: [PATCH 002/153] Add wrapper classes for JDK internals Continuation and ContinuationScope are JDK-private; wrapper classes are used to provide access via reflection --- .../wpilibj/commandsv3/Continuation.java | 166 ++++++++++++++++++ .../wpilibj/commandsv3/ContinuationScope.java | 47 +++++ 2 files changed, 213 insertions(+) create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java new file mode 100644 index 00000000000..3b7c9cf1eb7 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java @@ -0,0 +1,166 @@ +// 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.commandsv3; + +import java.lang.invoke.MethodHandle; +import java.lang.invoke.MethodHandles; +import java.lang.invoke.MethodType; +import java.lang.invoke.WrongMethodTypeException; + +/** A wrapper around the JDK internal Continuation class. */ +public final class Continuation { + // The underlying jdk.internal.vm.Continuation object + final Object continuation; + + static final Class jdk_internal_vm_Continuation; + private static final MethodHandle CONSTRUCTOR; + private static final MethodHandle YIELD; + private static final MethodHandle RUN; + private static final MethodHandle IS_DONE; + + private static final MethodHandle java_lang_thread_setContinuation; + + static { + try { + jdk_internal_vm_Continuation = Class.forName("jdk.internal.vm.Continuation"); + + var lookup = + MethodHandles.privateLookupIn(jdk_internal_vm_Continuation, MethodHandles.lookup()); + + CONSTRUCTOR = + lookup.findConstructor( + jdk_internal_vm_Continuation, + MethodType.methodType( + void.class, ContinuationScope.jdk_internal_vm_ContinuationScope, Runnable.class)); + + YIELD = + lookup.findStatic( + jdk_internal_vm_Continuation, + "yield", + MethodType.methodType( + boolean.class, ContinuationScope.jdk_internal_vm_ContinuationScope)); + + RUN = + lookup.findVirtual( + jdk_internal_vm_Continuation, "run", MethodType.methodType(void.class)); + + IS_DONE = + lookup.findVirtual( + jdk_internal_vm_Continuation, "isDone", MethodType.methodType(boolean.class)); + } catch (Throwable t) { + throw new ExceptionInInitializerError(t); + } + } + + static { + try { + var lookup = MethodHandles.privateLookupIn(Thread.class, MethodHandles.lookup()); + + java_lang_thread_setContinuation = + lookup.findVirtual( + Thread.class, + "setContinuation", + MethodType.methodType(void.class, Continuation.jdk_internal_vm_Continuation)); + } catch (Throwable t) { + throw new ExceptionInInitializerError(t); + } + } + + private final ContinuationScope scope; + + /** + * Constructs a continuation. + * + * @param scope the continuation's scope, used in yield + * @param target the continuation's body + */ + public Continuation(ContinuationScope scope, Runnable target) { + try { + this.continuation = CONSTRUCTOR.invoke(scope.continuationScope, target); + this.scope = scope; + } catch (Throwable t) { + throw new RuntimeException(t); + } + } + + /** + * Suspends the current continuations up to the given scope. + * + * @param scope The {@link ContinuationScope} to suspend + * @return {@code true} for success; {@code false} for failure + * @throws IllegalStateException if not currently in the given {@code scope}, + */ + public static boolean yield(ContinuationScope scope) { + try { + return (boolean) YIELD.invoke(scope.continuationScope); + } catch (Throwable t) { + throw new RuntimeException(t); + } + } + + /** + * Mounts and runs the continuation body. If suspended, continues it from the last suspend point. + */ + public void run() { + try { + RUN.invoke(continuation); + } catch (WrongMethodTypeException | ClassCastException e) { + throw new IllegalStateException("Unable to run the underlying continuation!", e); + } catch (RuntimeException e) { + // The bound task threw an exception; re-throw it + throw e; + } catch (Throwable t) { + // Other error type (eg StackOverflowError, OutOfMemoryError), wrap in an Error so it won't + // be caught by a naive `catch (Exception e)` statement + throw new Error(t); + } + } + + /** + * Tests whether this continuation is completed + * + * @return whether this continuation is completed + */ + public boolean isDone() { + try { + return (boolean) IS_DONE.invoke(continuation); + } catch (Throwable t) { + throw new RuntimeException(t); + } + } + + /** + * Mounds a continuation to the current thread. Accepts null for clearing the currently mounted + * continuation. + * + * @param continuation the continuation to mount + */ + public static void mountContinuation(Continuation continuation) { + try { + if (continuation == null) { + java_lang_thread_setContinuation.invoke(Thread.currentThread(), null); + } else { + java_lang_thread_setContinuation.invoke(Thread.currentThread(), continuation.continuation); + } + } catch (Throwable t) { + // Anything thrown internally by Thread.setContinuation. + // It only assigns to a field, no way to throw + // However, if the invocation fails for some reason, we'll end up with an + // IllegalStateException when attempting to run an unmounted continuation + } + } + + @Override + public String toString() { + return continuation.toString(); + } + + /** + * @see Continuation#yield(ContinuationScope) + */ + public boolean yield() { + return Continuation.yield(scope); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java new file mode 100644 index 00000000000..9f251138ff8 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java @@ -0,0 +1,47 @@ +// 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.commandsv3; + +import java.lang.invoke.MethodHandle; +import java.lang.invoke.MethodHandles; +import java.lang.invoke.MethodType; +import java.util.Objects; + +public final class ContinuationScope { + // The underlying jdk.internal.vm.ContinuationScope object + final Object continuationScope; + + static final Class jdk_internal_vm_ContinuationScope; + private static final MethodHandle CONSTRUCTOR; + + static { + try { + jdk_internal_vm_ContinuationScope = Class.forName("jdk.internal.vm.ContinuationScope"); + + var lookup = + MethodHandles.privateLookupIn(jdk_internal_vm_ContinuationScope, MethodHandles.lookup()); + + CONSTRUCTOR = + lookup.findConstructor( + jdk_internal_vm_ContinuationScope, MethodType.methodType(void.class, String.class)); + } catch (Throwable t) { + throw new ExceptionInInitializerError(t); + } + } + + public ContinuationScope(String name) { + Objects.requireNonNull(name); + try { + this.continuationScope = CONSTRUCTOR.invoke(name); + } catch (Throwable e) { + throw new RuntimeException(e); + } + } + + @Override + public String toString() { + return continuationScope.toString(); + } +} From 89e7471e3e2a7be33fc5307574f9ea8be2047b6f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:14:38 -0400 Subject: [PATCH 003/153] Add core classes --- .../wpi/first/wpilibj/commandsv3/Command.java | 344 +++++++++ .../wpilibj/commandsv3/CommandBuilder.java | 224 ++++++ .../commandsv3/CommandExecutionException.java | 34 + .../wpilibj/commandsv3/CommandState.java | 18 + .../first/wpilibj/commandsv3/Coroutine.java | 183 +++++ .../first/wpilibj/commandsv3/IdleCommand.java | 67 ++ .../wpilibj/commandsv3/ParallelGroup.java | 278 ++++++++ .../commandsv3/RequireableResource.java | 82 +++ .../first/wpilibj/commandsv3/Scheduler.java | 628 ++++++++++++++++ .../first/wpilibj/commandsv3/Sequence.java | 162 +++++ .../first/wpilibj/commandsv3/WaitCommand.java | 40 ++ .../commandsv3/proto/CommandProto.java | 57 ++ .../commandsv3/proto/ProtobufCommand.java | 670 ++++++++++++++++++ .../proto/ProtobufRequireableResource.java | 302 ++++++++ .../commandsv3/proto/ProtobufScheduler.java | 479 +++++++++++++ .../proto/RequireableResourceProto.java | 37 + .../wpilibj/commandsv3/proto/Scheduler.java | 63 ++ .../commandsv3/proto/SchedulerProto.java | 48 ++ commandsv3/src/main/proto/scheduler.proto | 32 + .../wpilibj/commandsv3/ParallelGroupTest.java | 235 ++++++ .../wpilibj/commandsv3/SchedulerTest.java | 668 +++++++++++++++++ .../wpilibj/commandsv3/SequenceTest.java | 84 +++ 22 files changed, 4735 insertions(+) create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java create mode 100644 commandsv3/src/main/proto/scheduler.proto create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java new file mode 100644 index 00000000000..63687f18aaa --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java @@ -0,0 +1,344 @@ +// 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.commandsv3; + +import edu.wpi.first.units.measure.Time; +import java.util.Collections; +import java.util.Set; +import java.util.function.BooleanSupplier; +import java.util.function.Consumer; + +/** + * Performs some task using one or more {@link RequireableResource resources} using the + * collaborative concurrency tools added in Java 21; namely, continuations. Continuations allow + * commands to be executed concurrently in a collaborative manner as coroutines. Instead of needing + * to split command behavior into distinct functions (initialize(), execute(), end(), and + * isFinished()), commands can be implemented with a single, imperative loop. + * + *

Note: Because coroutines are opt-in collaborate constructs, every + * command implementation must call {@link Coroutine#yield()} within any periodic + * loop. Failure to do so may result in an unrecoverable infinite loop. + * + * {@snippet lang = java: + * // A 2013-style class-based command definition + * class ClassBasedCommand extends Command { + * public ClassBasedCommand(Subsystem requiredSubsystem) { + * addRequirements(requiredSubsystem); + * } + * + * @Override + * public void initialize() {} + * + * @Override + * public void execute() {} + * + * @Override + * public void end(boolean interrupted) {} + * + * @Override + * public void isFinished() { return true; } + * + * @Override + * public String getName() { return "The Command"; } + * } + * + * Command command = new ClassBasedCommand(requiredSubsystem); + * + * // Or a 2020-style function-based command + * Command command = requiredSubsystem + * .runOnce(() -> initialize()) + * .andThen( + * requiredSubsystem + * .run(() -> execute()) + * .until(() -> isFinished()) + * .onFinish(() -> end()) + * ).withName("The Command"); + * + * // Can be represented with a 2025-style async-based definition + * Command command = requiredSubsystem.run((coroutine) -> { + * initialize(); + * while (!isFinished()) { + * coroutine.yield(); + * execute(); + * } + * end(); + * }).named("The Command"); + * } + */ +public interface Command { + /** The default command priority. */ + int DEFAULT_PRIORITY = 0; + + /** + * The lowest possible command priority. Commands with the lowest priority can be interrupted by + * any other command, including other minimum-priority commands. + */ + int LOWEST_PRIORITY = Integer.MIN_VALUE; + + /** + * The highest possible command priority. Commands with the highest priority can only be + * interrupted by other maximum-priority commands. + */ + int HIGHEST_PRIORITY = Integer.MAX_VALUE; + + /** + * Runs the command. Commands that need to periodically run until a goal state is reached should + * simply run a while loop like {@code while (!atGoal() && coroutine.yield()) { ... } }. + * + *

Warning: any loops in a command must call {@code coroutine.yield()}. + * Failure to do so will prevent anything else in your robot code from running. Commands are + * opt-in collaborative constructs; don't be greedy! + * + * @param coroutine the coroutine backing the command's execution + */ + void run(Coroutine coroutine); + + /** + * An optional lifecycle hook that can be implemented to execute some code whenever this command + * is cancelled before it naturally completes. Commands should be careful to do a single-shot + * cleanup (for example, setting a motor to zero volts) and not do any complex looping logic here. + */ + default void onCancel() { + // NOP by default + } + + /** + * The name of the command. + * + * @return the name of the command + */ + String name(); + + /** + * The set of resources required by the command. This is used by the scheduler to determine if two + * commands conflict with each other. Any singular resource may only be required by a single + * running command at a time. + * + * @return the set of resources required by the command + */ + Set requirements(); + + /** + * The priority of the command. If a command is scheduled that conflicts with another running or + * pending command, the relative priority values are compared. If the scheduled command is lower + * priority than the running command, then it will not be scheduled and the running command will + * continue to run. If it is the same or higher priority, then the running command will be + * canceled and the scheduled command will start to run. + * + * @return the priority of the command + */ + default int priority() { + return DEFAULT_PRIORITY; + } + + enum RobotDisabledBehavior { + /** + * Behavior that will prevent a command from running while the robot is disabled. A command with + * this behavior will be cancelled while running if the robot is disabled, and will not be able + * to be scheduled while disabled. + */ + CancelWhileDisabled, + /** + * Behavior that will allow a command to run while the robot is disabled. This allows safe + * commands - commands that do not try to move actuators - to still be able to run do perform + * tasks like updating data buffers or resetting sensors and odometry. Note that even if a + * command that does try to move actuators has this behavior, it will be unable to effect + * any movement due to the inbuilt safety mechanisms in the roboRIO and vendor hardware. + */ + RunWhileDisabled, + } + + /** + * The behavior of this command when the robot is disabled. Defaults to {@link + * RobotDisabledBehavior#CancelWhileDisabled}. + * + * @return the command's behavior during robot disable. + */ + default RobotDisabledBehavior robotDisabledBehavior() { + return RobotDisabledBehavior.CancelWhileDisabled; + } + + /** + * Checks if this command has a lower {@link #priority() priority} than another command. + * + * @param other the command to compare with + * @return true if this command has a lower priority than the other one, false otherwise + */ + default boolean isLowerPriorityThan(Command other) { + if (other == null) return false; + + return priority() < other.priority(); + } + + /** + * Checks if this command requires a particular resource. + * + * @param resource the resource to check + * @return true if the resource is a member of the required resources, false if not + */ + default boolean requires(RequireableResource resource) { + return requirements().contains(resource); + } + + /** + * Checks if this command conflicts with another command. + * + * @param other the commands to check against + * @return true if both commands require at least one of the same resource, false if both commands + * have completely different requirements + */ + default boolean conflictsWith(Command other) { + return !Collections.disjoint(requirements(), other.requirements()); + } + + /** + * Creates a new command that runs this one for a maximum duration, after which it is forcibly + * canceled. This is particularly useful for autonomous routines where you want to prevent your + * entire autonomous period spent stuck on a single action because a mechanism doesn't quite reach + * its setpoint (for example, spinning up a flywheel or driving to a particular location on the + * field). The resulting command will have the same name as this one. + * + * @param timeout the maximum duration that the command is permitted to run. Negative or zero + * values will result in the command running only once before being canceled. + * @return the timed out command. + */ + default Command withTimeout(Time timeout) { + return ParallelGroup.race(this, new WaitCommand(timeout)) + .named(name() + " [" + timeout.toLongString() + " timeout]"); + } + + /** + * Creates a command that does not require any hardware; that is, it does not affect the state of + * any physical objects. This is useful for commands that do some house cleaning work like + * resetting odometry and sensors that you don't want to interrupt a command that's controlling + * the resources it affects. + * + * @param impl the implementation of the command logic + * @return a builder that can be used to configure the resulting command + */ + static CommandBuilder noRequirements(Consumer impl) { + return new CommandBuilder().executing(impl); + } + + /** + * Starts creating a command that requires one or more resources. + * + * @param requirement The first required resource + * @param rest Any other required resources + * @return A command builder + */ + static CommandBuilder requiring(RequireableResource requirement, RequireableResource... rest) { + return new CommandBuilder().requiring(requirement).requiring(rest); + } + + /** + * Starts creating a command that runs a group of multiple commands in parallel. The command will + * complete when every command in the group has completed naturally. + * + * @param commands The commands to run in parallel + * @return A command builder + */ + static ParallelGroup.Builder parallel(Command... commands) { + return ParallelGroup.all(commands); + } + + /** + * Starts creating a command that runs a group of multiple commands in parallel. The command will + * complete when any command in the group has completed naturally; all other commands in the group + * will be canceled. + * + * @param commands The commands to run in parallel + * @return A command builder + */ + static ParallelGroup.Builder race(Command... commands) { + return ParallelGroup.race(commands); + } + + /** + * Starts creating a command that runs a group of multiple commands in sequence. The command will + * complete when the last command in the group has completed naturally. Commands in the group will + * run in the order they're passed to this method. + * + * @param commands The commands to run in sequence. + * @return A command builder + */ + static Sequence.Builder sequence(Command... commands) { + return Sequence.sequence(commands); + } + + /** + * Starts creating a command that simply waits for some condition to be met. The command will + * start without any requirements, but some may be added (if necessary) using {@link + * CommandBuilder#requiring(RequireableResource)}. + * + * @param condition The condition to wait for + * @return A command builder + */ + static CommandBuilder waitingFor(BooleanSupplier condition) { + return noRequirements( + coroutine -> { + while (!condition.getAsBoolean()) { + coroutine.yield(); + } + }); + } + + default ParallelGroup.Builder until(BooleanSupplier endCondition) { + return ParallelGroup.builder() + .optional(this, Command.waitingFor(endCondition).named("Until Condition")); + } + + /** + * Starts creating a command sequence, starting from this command and then running the next one. + * More commands can be added with the builder before naming and creating the sequence. + * + *

+ * + * {@snippet lang="java" : + * Sequence aThenBThenC = + * commandA() + * .andThen(commandB()) + * .andThen(commandC()) + * .withAutomaticName(); + * } + * + * @param next The command to run after this one in the sequence + * @return A sequence builder + */ + default Sequence.Builder andThen(Command next) { + return Sequence.builder().andThen(this).andThen(next); + } + + /** + * Starts creating a parallel command group, running this command alongside one or more other + * commands. The group will exit once every command has finished. + * + *

+ * + * {@snippet lang="java" : + * ParallelGroup abc = + * commandA() + * .alongWith(commandB(), commandC()) + * .withAutomaticName(); + * } + * + * @param parallel The commands to run in parallel with this one + * @return A parallel group builder + */ + default ParallelGroup.Builder alongWith(Command... parallel) { + return ParallelGroup.builder().requiring(this).requiring(parallel); + } + + /** + * Starts creating a parallel command group, running this command alongside one or more other + * commands. The group will exit after any command finishes. + * + * @param parallel The commands to run in parallel with this one + * @return A parallel group builder + */ + default ParallelGroup.Builder raceWith(Command... parallel) { + return ParallelGroup.builder().optional(this).optional(parallel); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java new file mode 100644 index 00000000000..55d9696344a --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java @@ -0,0 +1,224 @@ +// 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.commandsv3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.Arrays; +import java.util.Collection; +import java.util.HashSet; +import java.util.List; +import java.util.Objects; +import java.util.Set; +import java.util.function.Consumer; + +/** + * A builder that allows for all functionality of a command to be configured prior to creating it. + */ +public class CommandBuilder { + private final Set requirements = new HashSet<>(); + private Consumer impl; + private Runnable onCancel = () -> {}; + private String name; + private int priority = Command.DEFAULT_PRIORITY; + private Command.RobotDisabledBehavior disabledBehavior = + Command.RobotDisabledBehavior.CancelWhileDisabled; + + /** + * Adds a resource as a requirement for the command. + * + * @param resource The required resource + * @return The builder object, for chaining + * @see Command#requirements() + */ + public CommandBuilder requiring(RequireableResource resource) { + requireNonNullParam(resource, "resource", "CommandBuilder.requiring"); + + requirements.add(resource); + return this; + } + + /** + * Adds resources as requirements for the command. + * + * @param resources The required resources + * @return The builder object, for chaining + * @see Command#requirements() + */ + public CommandBuilder requiring(RequireableResource... resources) { + requireNonNullParam(resources, "resources", "CommandBuilder.requiring"); + for (int i = 0; i < resources.length; i++) { + requireNonNullParam(resources[i], "resources[" + i + "]", "CommandBuilder.requiring"); + } + + requirements.addAll(Arrays.asList(resources)); + return this; + } + + /** + * Adds resources as requirements for the command. + * + * @param resources The required resources + * @return The builder object, for chaining + * @see Command#requirements() + */ + public CommandBuilder requiring(Collection resources) { + requireNonNullParam(resources, "resources", "CommandBuilder.requiring"); + if (resources instanceof List l) { + for (int i = 0; i < l.size(); i++) { + requireNonNullParam(l.get(i), "resources[" + i + "]", "CommandBuilder.requiring"); + } + } else { + // non-indexable collection + for (var resource : resources) { + requireNonNullParam(resource, "resources", "CommandBuilder.requiring"); + } + } + + requirements.addAll(resources); + return this; + } + + /** + * Sets the name of the command. + * + * @param name The command's name + * @return The builder object, for chaining + * @see Command#name() + */ + public CommandBuilder withName(String name) { + requireNonNullParam(name, "name", "CommandBuilder.withName"); + + this.name = name; + return this; + } + + /** + * Creates the command based on what's been configured in the builder. + * + * @param name The name of the command + * @return The built command + * @throws NullPointerException if {@code name} is null or if the command body was not set using + * {@link #executing(Consumer)}. + * @see Command#name() + */ + public Command named(String name) { + return withName(name).make(); + } + + /** + * Sets the priority of the command. If not set, {@link Command#DEFAULT_PRIORITY} will be used. + * + * @param priority The priority of the command + * @return The builder object, for chaining + * @see Command#priority() + */ + public CommandBuilder withPriority(int priority) { + this.priority = priority; + return this; + } + + /** + * Marks the command as being able to run while the robot is disabled. + * + * @return The builder object, for chaining + * @see Command#robotDisabledBehavior() + */ + public CommandBuilder ignoringDisable() { + return withDisabledBehavior(Command.RobotDisabledBehavior.RunWhileDisabled); + } + + /** + * Gives the command the given behavior when the robot is disabled. + * + * @param behavior The behavior when the robot is disabled + * @return The builder object, for chaining + * @see Command#robotDisabledBehavior() + * @see #ignoringDisable() + */ + public CommandBuilder withDisabledBehavior(Command.RobotDisabledBehavior behavior) { + requireNonNullParam(behavior, "behavior", "CommandBuilder.withDisabledBehavior"); + + this.disabledBehavior = behavior; + return this; + } + + /** + * Sets the code that the command will execute when it's being run by the scheduler. + * + * @param impl The command implementation + * @return The builder object, for chaining + * @see Command#run(Coroutine) + */ + public CommandBuilder executing(Consumer impl) { + requireNonNullParam(impl, "impl", "CommandBuilder.executing"); + + this.impl = impl; + return this; + } + + /** + * Sets the code that the command will execute if it's cancelled while running. + * + * @param onCancel The cancellation callback + * @return The builder object, for chaining. + * @see Command#onCancel() + */ + public CommandBuilder whenCanceled(Runnable onCancel) { + requireNonNullParam(onCancel, "onCancel", "CommandBuilder.whenCanceled"); + + this.onCancel = onCancel; + return this; + } + + /** + * Creates the command. + * + * @return The built command + * @throws NullPointerException An NPE if either the command {@link #named(String) name} or {@link + * #executing(Consumer) implementation} were not configured before calling this method. + */ + public Command make() { + Objects.requireNonNull(name, "Name was not specified"); + Objects.requireNonNull(impl, "Command logic was not specified"); + + return new Command() { + @Override + public void run(Coroutine coroutine) { + impl.accept(coroutine); + } + + @Override + public void onCancel() { + onCancel.run(); + } + + @Override + public String name() { + return name; + } + + @Override + public Set requirements() { + return requirements; + } + + @Override + public int priority() { + return priority; + } + + @Override + public RobotDisabledBehavior robotDisabledBehavior() { + return disabledBehavior; + } + + @Override + public String toString() { + return name(); + } + }; + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java new file mode 100644 index 00000000000..88260885e30 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java @@ -0,0 +1,34 @@ +// 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.commandsv3; + +/** + * An exception thrown when a {@link Command} encounters an error while running in a {@link + * Scheduler}. + */ +public class CommandExecutionException extends RuntimeException { + /** The command that had the exception. */ + private final Command command; + + /** + * Creates a new CommandExecutionException. + * + * @param command the command that encountered the exception + * @param cause the exception itself + */ + public CommandExecutionException(Command command, Throwable cause) { + super("An exception was detected while running command " + command.name(), cause); + this.command = command; + } + + /** + * Gets the command that encountered the exception. + * + * @return the command + */ + public Command getCommand() { + return command; + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java new file mode 100644 index 00000000000..bda4975be36 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java @@ -0,0 +1,18 @@ +// 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.commandsv3; + +/** + * Represents the state of a command as it is executed by the scheduler. + * + * @param command The command being tracked. + * @param parent The parent command composition that scheduled the tracked command. Null if the + * command was scheduled by a top level construct like trigger bindings or manually scheduled by + * a user. For deeply nested compositions, this tracks the direct parent command that + * invoked the schedule() call; in this manner, an ancestry tree can be built, where each {@code + * CommandState} object references a parent node in the tree. + * @param coroutine The coroutine to which the command is bound. + */ +record CommandState(Command command, Command parent, Coroutine coroutine) {} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java new file mode 100644 index 00000000000..c90cdaea416 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java @@ -0,0 +1,183 @@ +// 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.commandsv3; + +import edu.wpi.first.units.measure.Time; +import java.util.Arrays; +import java.util.Collection; +import java.util.function.Consumer; + +/** + * A coroutine object is injected into command's {@link Command#run(Coroutine)} method to allow + * commands to yield and compositions to run other commands. + */ +public final class Coroutine { + private final Scheduler scheduler; + private final Continuation backingContinuation; + + Coroutine(Scheduler scheduler, ContinuationScope scope, Consumer callback) { + this.scheduler = scheduler; + this.backingContinuation = + new Continuation( + scope, + () -> { + callback.accept(this); + }); + } + + /** + * Yields control back to the scheduler to allow other commands to execute. This can be thought of + * as "pausing" the currently executing command. + * + * @return true + */ + public boolean yield() { + return backingContinuation.yield(); + } + + /** + * Parks the current command. No code in a command declared after calling {@code park()} will be + * executed. A parked command will never complete naturally and must be interrupted or cancelled. + */ + @SuppressWarnings("InfiniteLoopStatement") + public void park() { + while (true) { + Coroutine.this.yield(); + } + } + + /** + * Awaits completion of a command. If the command is not currently scheduled or running, it will + * be scheduled automatically. + * + * @param command the command to await + * @throws IllegalStateException if the given command uses a resource not owned by the calling + * command + */ + public void await(Command command) { + if (!scheduler.isScheduledOrRunning(command)) { + scheduler.schedule(command); + } + + while (scheduler.isScheduledOrRunning(command)) { + // If the command is a one-shot, then the schedule call will completely execute the command. + // There would be nothing to await + this.yield(); + } + } + + /** + * Awaits completion of all given commands. If any command is not current scheduled or running, it + * will be scheduled. + * + * @param commands the commands to await + * @throws IllegalArgumentException if any of the commands conflict with each other + */ + public void awaitAll(Collection commands) { + // Schedule anything that's not already queued or running + for (var command : commands) { + if (!scheduler.isScheduledOrRunning(command)) { + scheduler.schedule(command); + } + } + + while (commands.stream().anyMatch(scheduler::isScheduledOrRunning)) { + this.yield(); + } + + // The scheduler will clean up anything that's still running at this point + } + + /** + * Awaits completion of all given commands. If any command is not current scheduled or running, it + * will be scheduled. + * + * @param commands the commands to await + * @throws IllegalArgumentException if any of the commands conflict with each other + */ + public void awaitAll(Command... commands) { + awaitAll(Arrays.asList(commands)); + } + + /** + * Awaits completion of any given commands. Any command that's not already scheduled or running + * will be scheduled. After any of the given commands completes, the rest will be canceled. + * + * @param commands the commands to await + * @throws IllegalArgumentException if any of the commands conflict with each other + */ + public void awaitAny(Collection commands) { + // Schedule anything that's not already queued or running + for (var command : commands) { + if (!scheduler.isScheduledOrRunning(command)) { + scheduler.schedule(command); + } + } + + while (commands.stream().allMatch(scheduler::isScheduledOrRunning)) { + this.yield(); + } + } + + /** + * Awaits completion of any given commands. Any command that's not already scheduled or running + * will be scheduled. After any of the given commands completes, the rest will be canceled. + * + * @param commands the commands to await + * @throws IllegalArgumentException if any of the commands conflict with each other + */ + public void awaitAny(Command... commands) { + awaitAny(Arrays.asList(commands)); + } + + /** + * Waits for some duration of time to elapse. Returns immediately if the given duration is zero or + * negative. Call this within a command or command composition to introduce a simple delay. + * + *

For example, a basic autonomous routine that drives straight for 5 seconds: + * + * {@snippet lang = java : + * Command timedDrive() { + * return drivebase.run((coroutine) -> { + * drivebase.tankDrive(1, 1); + * coroutine.wait(Seconds.of(5)); + * drivebase.stop(); + * }).named("Timed Drive"); + * } + * } + * + * @param duration the duration of time to wait + */ + public void wait(Time duration) { + await(new WaitCommand(duration)); + } + + /** + * Advanced users only: this permits access to the backing command scheduler to run custom logic + * not provided by the standard coroutine methods. Any commands manually scheduled through this + * will be cancelled when the parent command exits - it's not possible to "fork" a command that + * lives longer than the command that scheduled it. + * + * @return the command scheduler backing this coroutine + */ + public Scheduler scheduler() { + return scheduler; + } + + // Package-private for interaction with the scheduler. + // These functions are not intended for team use. + + void runToYieldPoint() { + backingContinuation.run(); + } + + void mount() { + Continuation.mountContinuation(backingContinuation); + } + + boolean isDone() { + return backingContinuation.isDone(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java new file mode 100644 index 00000000000..33e922b1736 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java @@ -0,0 +1,67 @@ +// 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.commandsv3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.Objects; +import java.util.Set; + +/** + * An idle command that owns a resource without doing anything. It has the lowest possible priority, + * and can be interrupted by any other command that requires the same resource. Cancellation and + * interruption function like a normal command. + */ +public final class IdleCommand implements Command { + private final RequireableResource resource; + + /** + * @param resource the resource to idle. + */ + public IdleCommand(RequireableResource resource) { + this.resource = requireNonNullParam(resource, "resource", "IdleCommand"); + } + + @Override + public void run(Coroutine coroutine) { + coroutine.park(); + } + + @Override + public Set requirements() { + return Set.of(resource); + } + + @Override + public String name() { + return resource.getName() + "[IDLE]"; + } + + @Override + public int priority() { + // lowest priority - an idle command can be interrupted by anything else + return LOWEST_PRIORITY; + } + + @Override + public String toString() { + return name(); + } + + @Override + public RobotDisabledBehavior robotDisabledBehavior() { + return RobotDisabledBehavior.RunWhileDisabled; + } + + @Override + public boolean equals(Object obj) { + return obj instanceof IdleCommand other && Objects.equals(this.resource, other.resource); + } + + @Override + public int hashCode() { + return Objects.hash(resource); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java new file mode 100644 index 00000000000..ec164b7be13 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java @@ -0,0 +1,278 @@ +// 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.commandsv3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.Arrays; +import java.util.Collection; +import java.util.HashSet; +import java.util.LinkedHashSet; +import java.util.Set; +import java.util.function.BooleanSupplier; +import java.util.stream.Collectors; + +/** + * A type of command that runs multiple other commands in parallel. The group will end after all + * required commands have completed; if no command is explicitly required for completion, then the + * group will end after any command in the group finishes. Any commands still running when the group + * has reached its completion condition will be cancelled. + */ +public class ParallelGroup implements Command { + private final Collection commands = new LinkedHashSet<>(); + private final Collection requiredCommands = new HashSet<>(); + private final Set requirements = new HashSet<>(); + private final String name; + private final int priority; + private RobotDisabledBehavior disabledBehavior; + + /** + * Creates a new parallel group. + * + * @param name The name of the group. + * @param allCommands All the commands to run in parallel. + * @param requiredCommands The commands that are required to completed for the group to finish. If + * this is empty, then the group will finish when any command in it has completed. + */ + public ParallelGroup( + String name, Collection allCommands, Collection requiredCommands) { + requireNonNullParam(name, "name", "ParallelGroup"); + requireNonNullParam(allCommands, "allCommands", "ParallelGroup"); + requireNonNullParam(requiredCommands, "requiredCommands", "ParallelGroup"); + + allCommands.forEach( + c -> { + requireNonNullParam(c, "allCommands[x]", "ParallelGroup"); + }); + requiredCommands.forEach( + c -> { + requireNonNullParam(c, "requiredCommands[x]", "ParallelGroup"); + }); + + if (!allCommands.containsAll(requiredCommands)) { + throw new IllegalArgumentException("Required commands must also be composed"); + } + + for (Command c1 : allCommands) { + for (Command c2 : allCommands) { + if (c1 == c2) { + // Commands can't conflict with themselves + continue; + } + if (c1.conflictsWith(c2)) { + throw new IllegalArgumentException( + "Commands in a parallel composition cannot require the same resources. " + + c1.name() + + " and " + + c2.name() + + " conflict."); + } + } + } + + this.name = name; + this.commands.addAll(allCommands); + this.requiredCommands.addAll(requiredCommands); + + for (var command : allCommands) { + requirements.addAll(command.requirements()); + } + + this.priority = + allCommands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); + + this.disabledBehavior = RobotDisabledBehavior.RunWhileDisabled; + for (Command command : allCommands) { + if (command.robotDisabledBehavior() == RobotDisabledBehavior.CancelWhileDisabled) { + this.disabledBehavior = RobotDisabledBehavior.CancelWhileDisabled; + break; + } + } + } + + /** + * Creates a parallel group that runs all the given commands until any of them finish. + * + * @param commands the commands to run in parallel + * @return the group + */ + public static Builder race(Command... commands) { + return builder().optional(commands); + } + + /** + * Creates a parallel group that runs all the given commands until they all finish. If a command + * finishes early, its required resources will be idle (uncommanded) until the group completes. + * + * @param commands the commands to run in parallel + * @return the group + */ + public static Builder all(Command... commands) { + return builder().requiring(commands); + } + + @Override + public void run(Coroutine coroutine) { + if (requiredCommands.isEmpty()) { + // No command is explicitly required to complete + // Schedule everything and wait for the first one to complete + coroutine.awaitAny(commands); + } else { + // At least one command is required to complete + // Schedule all the non-required commands (the scheduler will automatically cancel them + // when this group completes), and await completion of all the required commands + commands.forEach(coroutine.scheduler()::schedule); + coroutine.awaitAll(requiredCommands); + } + } + + @Override + public String name() { + return name; + } + + @Override + public Set requirements() { + return requirements; + } + + @Override + public int priority() { + return priority; + } + + @Override + public RobotDisabledBehavior robotDisabledBehavior() { + return disabledBehavior; + } + + @Override + public String toString() { + return "ParallelGroup[name=" + name + "]"; + } + + public static Builder builder() { + return new Builder(); + } + + public static class Builder { + private final Set commands = new LinkedHashSet<>(); + private final Set requiredCommands = new LinkedHashSet<>(); + private BooleanSupplier endCondition = null; + + /** + * Adds one or more optional commands to the group. They will not be required to complete for + * the parallel group to exit, and will be canceled once all required commands have finished. + * + * @param commands The optional commands to add to the group + * @return The builder object, for chaining + */ + public Builder optional(Command... commands) { + this.commands.addAll(Arrays.asList(commands)); + return this; + } + + /** + * Adds one or more required commands to the group. All required commands will need to complete + * for the group to exit. + * + * @param commands The required commands to add to the group + * @return The builder object, for chaining + */ + public Builder requiring(Command... commands) { + requiredCommands.addAll(Arrays.asList(commands)); + this.commands.addAll(requiredCommands); + return this; + } + + /** + * Forces the group to be a pure race, where the group will finish after the first command in + * the group completes. All other commands in the group will be canceled. + * + * @return The builder object, for chaining + */ + public Builder racing() { + requiredCommands.clear(); + return this; + } + + /** + * Forces the group to require all its commands to complete, overriding any configured race or + * deadline behaviors. The group will only exit once every command has completed. + * + * @return The builder object, for chaining + */ + public Builder requireAll() { + requiredCommands.clear(); + requiredCommands.addAll(commands); + return this; + } + + /** + * Adds an end condition to the command group. If this condition is met before all required + * commands have completed, the group will exit early. If multiple end conditions are added + * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end + * condition added will be used and any previously configured condition will be overridden. + * + * @param condition The end condition for the group + * @return The builder object, for chaining + */ + public Builder until(BooleanSupplier condition) { + endCondition = condition; + return this; + } + + /** + * Creates the group, using the provided named. The group will require everything that the + * commands in the group require, and will have a priority level equal to the highest priority + * among those commands. + * + * @param name The name of the parallel group + * @return The built group + */ + public ParallelGroup named(String name) { + var group = new ParallelGroup(name, commands, requiredCommands); + if (endCondition == null) { + // No custom end condition, return the group as is + return group; + } + + // We have a custom end condition, so we need to wrap the group in a race + return builder() + .optional(group, Command.waitingFor(endCondition).named("Until Condition")) + .named(name); + } + + /** + * Creates the group, giving it a name based on the commands within the group. + * + * @return The built group + */ + public ParallelGroup withAutomaticName() { + // eg "(CommandA & CommandB & CommandC)" + String required = + requiredCommands.stream().map(Command::name).collect(Collectors.joining(" & ", "(", ")")); + + var optionalCommands = new LinkedHashSet<>(commands); + optionalCommands.removeAll(requiredCommands); + // eg "(CommandA | CommandB | CommandC)" + String optional = + optionalCommands.stream().map(Command::name).collect(Collectors.joining(" | ", "(", ")")); + + if (requiredCommands.isEmpty()) { + // No required commands, pure race + return named(optional); + } else if (optionalCommands.isEmpty()) { + // Everything required + return named(required); + } else { + // Some form of deadline + // eg "[(CommandA & CommandB) * (CommandX | CommandY | ...)]" + String name = "[%s * %s]".formatted(required, optional); + return named(name); + } + } + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java new file mode 100644 index 00000000000..b79f38f745e --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java @@ -0,0 +1,82 @@ +// 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.commandsv3; + +import edu.wpi.first.units.measure.Time; +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import java.util.List; +import java.util.function.Consumer; + +@SuppressWarnings("this-escape") +public class RequireableResource implements Sendable { + private final String name; + + private final Scheduler registeredScheduler; + + public RequireableResource(String name) { + this(name, Scheduler.getInstance()); + } + + public RequireableResource(String name, Scheduler scheduler) { + this.name = name; + this.registeredScheduler = scheduler; + setDefaultCommand(idle()); + } + + public String getName() { + return name; + } + + /** + * Sets the default command to run on the resource when no other command is scheduled. The default + * command's priority is effectively the minimum allowable priority for any command requiring a + * resource. For this reason, it's required that a default command have a priority less than + * {@link Command#DEFAULT_PRIORITY} to prevent it from blocking other, non-default commands from + * running. + * + *

The default command is initially an idle command that merely parks the execution thread. + * This command has the lowest possible priority so as to allow any other command to run. + * + * @param defaultCommand the new default command + */ + public void setDefaultCommand(Command defaultCommand) { + registeredScheduler.scheduleAsDefaultCommand(this, defaultCommand); + } + + public Command getDefaultCommand() { + return registeredScheduler.getDefaultCommandFor(this); + } + + public CommandBuilder run(Consumer command) { + return new CommandBuilder().requiring(this).executing(command); + } + + public Command idle() { + return new IdleCommand(this); + } + + public Command idle(Time duration) { + return idle().withTimeout(duration); + } + + public List getRunningCommands() { + return registeredScheduler.getRunningCommandsFor(this); + } + + @Override + public String toString() { + return name; + } + + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("RequireableResource"); + builder.addStringArrayProperty( + "Current Commands", + () -> getRunningCommands().stream().map(Command::name).toArray(String[]::new), + null); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java new file mode 100644 index 00000000000..d8f515a1084 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java @@ -0,0 +1,628 @@ +// 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.commandsv3; + +import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.commandsv3.proto.SchedulerProto; +import edu.wpi.first.wpilibj.event.EventLoop; +import java.util.ArrayList; +import java.util.Collection; +import java.util.Collections; +import java.util.LinkedHashMap; +import java.util.LinkedHashSet; +import java.util.List; +import java.util.Map; +import java.util.Set; +import java.util.Stack; +import java.util.function.Consumer; +import java.util.stream.Collectors; + +/** Manages the lifecycles of {@link Coroutine}-based {@link Command Commands}. */ +public class Scheduler implements ProtobufSerializable { + private final Map defaultCommands = new LinkedHashMap<>(); + + /** The set of commands scheduled since the start of the previous run. */ + private final Set onDeck = new LinkedHashSet<>(); + + /** The states of all running commands (does not include on deck commands). */ + private final Map commandStates = new LinkedHashMap<>(); + + /** + * The stack of currently executing commands. Child commands are pushed onto the stack and popped + * when they complete. Use {@link #currentState()} and {@link #currentCommand()} to get the + * currently executing command or its state. + */ + private final Stack executingCommands = new Stack<>(); + + /** The periodic callbacks to run, outside of the command structure. */ + private final List periodicCallbacks = new ArrayList<>(); + + /** Event loop for trigger bindings. */ + private final EventLoop eventLoop = new EventLoop(); + + /** The scope for continuations to yield to. */ + private final ContinuationScope scope = new ContinuationScope("coroutine commands"); + + public static final SchedulerProto proto = new SchedulerProto(); + + /** The default scheduler instance. */ + private static final Scheduler defaultScheduler = new Scheduler(); + + /** + * Gets the default scheduler instance for use in a robot program. Some built in command types use + * the default scheduler and will not work as expected if used on another scheduler instance. + * + * @return the default scheduler instance. + */ + public static Scheduler getInstance() { + return defaultScheduler; + } + + public Scheduler() {} + + /** + * Sets the default command for a resource. The command must require the resource, and cannot + * require any others. Default commands must have a lower priority than {@link + * Command#DEFAULT_PRIORITY} to function properly. + * + * @param resource the resource for which to set the default command + * @param defaultCommand the default command to execute on the resource + * @throws IllegalArgumentException if the command does not meet the requirements for being a + * default command + */ + public void scheduleAsDefaultCommand(RequireableResource resource, Command defaultCommand) { + if (!defaultCommand.requires(resource)) { + throw new IllegalArgumentException("A resource's default command must require that resource"); + } + + if (defaultCommand.requirements().size() > 1) { + throw new IllegalArgumentException( + "A resource's default command cannot require other resources"); + } + + if (defaultCommand.priority() >= Command.DEFAULT_PRIORITY) { + throw new IllegalArgumentException("Default commands must be low priority"); + } + + defaultCommands.put(resource, defaultCommand); + schedule(defaultCommand); + } + + /** + * Gets the default command set for a resource. + * + * @param resource The resource + * @return The default command, or null if no default command was ever set + */ + public Command getDefaultCommandFor(RequireableResource resource) { + return defaultCommands.get(resource); + } + + /** + * Adds a callback to run as part of the scheduler. The callback should not manipulate or control + * any resources, but can be used to log information, update data (such as simulations or LED data + * buffers), or perform some other helpful task. The callback is responsible for managing its own + * control flow and end conditions. If you want to run a single task periodically for the entire + * lifespan of the scheduler, use {@link #addPeriodic(Runnable)}. + * + *

Note: Like commands, any loops in the callback must appropriately yield + * control back to the scheduler with {@link Coroutine#yield} or risk stalling your program in an + * unrecoverable infinite loop! + * + * @param callback the callback to sideload + */ + public void sideload(Consumer callback) { + var coroutine = new Coroutine(this, scope, callback); + periodicCallbacks.add(coroutine); + } + + /** + * Adds a task to run repeatedly for as long as the scheduler runs. This internally handles the + * looping and control yielding necessary for proper function. The callback will run at the same + * periodic frequency as the scheduler. + * + *

For example: + * + *

{@code
+   * scheduler.addPeriodic(() -> leds.setData(ledDataBuffer));
+   * scheduler.addPeriodic(() -> {
+   *   SmartDashboard.putNumber("X", getX());
+   *   SmartDashboard.putNumber("Y", getY());
+   * });
+   * }
+ * + * @param callback the periodic function to run + */ + public void addPeriodic(Runnable callback) { + sideload( + (coroutine) -> { + while (coroutine.yield()) { + callback.run(); + } + }); + } + + public enum ScheduleResult { + /** The command was successfully scheduled and added to the queue. */ + SUCCESS, + /** The command is already scheduled or running. */ + ALREADY_RUNNING, + /** The command is a lower priority and conflicts with a command that's already running. */ + LOWER_PRIORITY_THAN_RUNNING_COMMAND, + } + + /** + * Schedules a command to run. If a running command schedules another command (for example, + * parallel groups will do this), then the new command is assumed to be a bound child of the + * running command. Child commands will automatically be cancelled by the scheduler when their + * parent command completes or is canceled. Child commands will also immediately begin execution, + * without needing to wait for the next {@link #run()} invocation. This allows highly nested + * compositions to begin running the actual meaningful commands sooner without needing to wait one + * scheduler cycle per nesting level; with the default 20ms update period, 5 levels of nesting + * would be enough to delay actions by 100 milliseconds - instead of only 20. + * + *

Does nothing if the command is already scheduled or running, or requires at least one + * resource already used by a higher priority command. + * + *

If one command schedules another ("parent" and "fork"), the forked command will be canceled + * when the parent command completes. It is not possible to fork a command and have it live longer + * than the command that forked it. + * + * @param command the command to schedule + * @throws IllegalArgumentException if scheduled by a command composition that has already + * scheduled another command that shares at least one required resource + */ + public ScheduleResult schedule(Command command) { + if (isScheduledOrRunning(command)) { + return ScheduleResult.ALREADY_RUNNING; + } + + if (!isSchedulable(command)) { + return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; + } + + // If scheduled within a composition, prevent the composition from scheduling multiple + // conflicting commands + // TODO: Should we return quietly instead of throwing an exception? + // Should we cancel the sibling? + var siblings = potentialSiblings(); + var conflictingSibling = siblings.stream().filter(command::conflictsWith).findFirst(); + if (conflictingSibling.isPresent()) { + var conflicts = new ArrayList<>(command.requirements()); + conflicts.retainAll(conflictingSibling.get().requirements()); + throw new IllegalArgumentException( + "Command " + + command.name() + + " requires resources that are already used by " + + conflictingSibling.get().name() + + ". Both require " + + conflicts.stream() + .map(RequireableResource::getName) + .collect(Collectors.joining(", "))); + } + + for (var scheduledState : onDeck) { + if (!command.conflictsWith(scheduledState.command())) { + // No shared requirements, skip + continue; + } + if (command.isLowerPriorityThan(scheduledState.command())) { + // Lower priority than an already-scheduled (but not yet running) command that requires at + // one of the same resource. Ignore it. + return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; + } + } + + // Evict conflicting on-deck commands + // We check above if the input command is lower priority than any of these, + // so at this point we're guaranteed to be >= priority than anything already on deck + evictConflictingOnDeckCommands(command); + + var state = new CommandState(command, currentCommand(), buildCoroutine(command)); + + if (currentState() != null) { + // Scheduling a child command while running. Start it immediately instead of waiting a full + // cycle. This prevents issues with deeply nested command groups taking many scheduler cycles + // to start running the commands that actually /do/ things + evictConflictingRunningCommands(state); + commandStates.put(command, state); + runCommand(state); + } else { + // Scheduling outside a command, add it to the pending set. If it's not overridden by another + // conflicting command being scheduled in the same scheduler loop, it'll be promoted and + // start to run when #runCommands() is called + onDeck.add(state); + } + + return ScheduleResult.SUCCESS; + } + + private boolean isSchedulable(Command command) { + if (currentState() != null) { + // Bypass scheduling check if being scheduled as a nested command. + // The schedule() method will throw an error when attempting to schedule a nested command + // that requires a resource that the parent doesn't + return true; + } + + // Scheduling from outside a command, eg a trigger binding or manual schedule call + // Check for conflicts with the commands that are already running + for (Command c : commandStates.keySet()) { + if (c.conflictsWith(command) && command.isLowerPriorityThan(c)) { + return false; + } + } + + return true; + } + + private Collection potentialSiblings() { + var siblings = new ArrayList(); + for (var state : commandStates.values()) { + if (state.parent() != null && state.parent() == currentCommand()) { + siblings.add(state.command()); + } + } + for (var state : onDeck) { + if (state.parent() != null && state.parent() == currentCommand()) { + siblings.add(state.command()); + } + } + + return siblings; + } + + private void evictConflictingOnDeckCommands(Command command) { + for (var iterator = onDeck.iterator(); iterator.hasNext(); ) { + var scheduledState = iterator.next(); + var scheduledCommand = scheduledState.command(); + if (scheduledCommand.conflictsWith(command)) { + // Remove the lower priority conflicting command from the on deck commands. + // We don't need to call removeOrphanedChildren here because it hasn't started yet, + // meaning it hasn't had a chance to schedule any children + iterator.remove(); + } + } + } + + /** + * Cancels all running commands with which an incoming state conflicts. Ancestor commands will not + * be canceled. + */ + private void evictConflictingRunningCommands(CommandState incomingState) { + // The set of root states with which the incoming state conflicts but does not inherit from + Set conflictingRootStates = + commandStates.values().stream() + .filter(state -> incomingState.command().conflictsWith(state.command())) + .filter(state -> !inheritsFrom(incomingState, state.command())) + .map( + state -> { + CommandState root = state; + while (root.parent() != null) { + root = commandStates.get(root.parent()); + } + return root; + }) + .collect(Collectors.toSet()); + + // Cancel the root commands + for (var conflictingState : conflictingRootStates) { + cancel(conflictingState.command()); + } + } + + /** + * Checks if a particular command is an ancestor of another. + * + * @param state the state to check + * @param ancestor the potential ancestor for which to search + * @return true if {@code ancestor} is the direct parent or indirect ancestor, false if not + */ + private boolean inheritsFrom(CommandState state, Command ancestor) { + if (state.parent() == null) { + // No parent, cannot inherit + return false; + } + if (!commandStates.containsKey(ancestor)) { + // The given ancestor isn't running + return false; + } + if (state.parent() == ancestor) { + // Direct child + return true; + } + // Check if the command's parent inherits from the given ancestor + return commandStates.values().stream() + .filter(s -> state.parent() == s.command()) + .anyMatch(s -> inheritsFrom(s, ancestor)); + } + + /** + * Cancels a command and any other command scheduled by it. This occurs immediately and does not + * need to wait for a call to {@link #run()}. Any command that it scheduled will also be canceled + * to ensure commands within compositions do not continue to run. + * + *

This has no effect if the given command is not currently scheduled or running. + * + * @param command the command to cancel + */ + public void cancel(Command command) { + boolean running = isRunning(command); + + // Evict the command. The next call to run() will schedule the default command for all its + // required resources, unless another command requiring those resources is scheduled between + // calling cancel() and calling run() + commandStates.remove(command); + onDeck.removeIf(state -> state.command() == command); + + if (running) { + // Only run the hook if the command was running. If it was on deck or not + // even in the scheduler at the time, then there's nothing to do + command.onCancel(); + } + + // Clean up any orphaned child commands; their lifespan must not exceed the parent's + removeOrphanedChildren(command); + } + + /** + * Updates the command scheduler. This will process trigger bindings on anything attached to the + * {@link #getDefaultEventLoop() default event loop}, begin running any commands scheduled since + * the previous call to {@code run()}, process periodic callbacks added with {@link + * #addPeriodic(Runnable)} and {@link #sideload(Consumer)}, update running commands, and schedule + * default commands for any resources that are not owned by a running command. + * + *

This method is intended to be called in a periodic loop like {@link + * TimedRobot#robotPeriodic()} + */ + public void run() { + // Process triggers first; these tend to queue and cancel commands + eventLoop.poll(); + + runPeriodicSideloads(); + promoteScheduledCommands(); + runCommands(); + scheduleDefaultCommands(); + } + + private void promoteScheduledCommands() { + // Clear any commands that conflict with the scheduled set + for (var queuedState : onDeck) { + evictConflictingRunningCommands(queuedState); + } + + // Move any scheduled commands to the running set + for (var queuedState : onDeck) { + commandStates.put(queuedState.command(), queuedState); + } + + // Clear the set of on-deck commands, + // since we just put them all into the set of running commands + onDeck.clear(); + } + + private void runPeriodicSideloads() { + // Update periodic callbacks + for (Coroutine coroutine : periodicCallbacks) { + coroutine.mount(); + try { + coroutine.runToYieldPoint(); + } finally { + Continuation.mountContinuation(null); + } + } + + // And remove any periodic callbacks that have completed + periodicCallbacks.removeIf(Coroutine::isDone); + } + + private void runCommands() { + // Tick every command that hasn't been completed yet + for (var state : List.copyOf(commandStates.values())) { + runCommand(state); + } + } + + private void runCommand(CommandState state) { + final var command = state.command(); + var coroutine = state.coroutine(); + + if (!commandStates.containsKey(command)) { + // Probably canceled by an owning composition, do not run + return; + } + + var previousState = currentState(); + + coroutine.mount(); + try { + executingCommands.push(state); + coroutine.runToYieldPoint(); + } finally { + if (currentState() == state) { + // Remove the command we just ran from the top of the stack + executingCommands.pop(); + } + if (previousState != null) { + // Remount the parent command, if there is one + previousState.coroutine().mount(); + } + } + + if (coroutine.isDone()) { + // Immediately check if the command has completed and remove any children commands. + // This prevents child commands from being executed one extra time in the run() loop + commandStates.remove(command); + removeOrphanedChildren(command); + } + } + + /** + * Gets the currently executing command state, or null if no command is currently executing. + * + * @return the currently executing command state + */ + private CommandState currentState() { + if (executingCommands.isEmpty()) { + // Avoid EmptyStackException + return null; + } + + return executingCommands.peek(); + } + + /** + * Gets the currently executing command, or null if no command is currently executing. + * + * @return the currently executing command + */ + private Command currentCommand() { + var state = currentState(); + if (state == null) { + return null; + } + + return state.command(); + } + + private void scheduleDefaultCommands() { + // Schedule the default commands for every resource that doesn't currently have a running or + // scheduled command. + defaultCommands.forEach( + (resource, defaultCommand) -> { + if (commandStates.keySet().stream().noneMatch(c -> c.requires(resource)) + && onDeck.stream().noneMatch(c -> c.command().requires(resource))) { + // Nothing currently running or scheduled + // Schedule the resource's default command, if it has one + if (defaultCommand != null) { + schedule(defaultCommand); + } + } + }); + } + + /** + * Removes all commands descended from a parent command. This is used to ensure that any command + * scheduled within a composition or group cannot live longer than any ancestor. + * + * @param parent the root command whose descendants to remove from the scheduler + */ + private void removeOrphanedChildren(Command parent) { + commandStates.entrySet().stream() + .filter(e -> e.getValue().parent() == parent) + .toList() // copy to an intermediate list to avoid concurrent modification + .forEach(e -> cancel(e.getKey())); + } + + /** + * Builds a coroutine object that the command will be bound to. The coroutine will be scoped to + * this scheduler object and cannot be used by another scheduler instance. + * + * @param command the command for which to build a coroutine + * @return the binding coroutine + */ + private Coroutine buildCoroutine(Command command) { + return new Coroutine( + this, + scope, + coroutine -> { + try { + command.run(coroutine); + } catch (Exception e) { + throw new CommandExecutionException(command, e); + } + }); + } + + /** + * Checks if a command is currently running. + * + * @param command the command to check + * @return true if the command is running, false if not + */ + public boolean isRunning(Command command) { + return commandStates.containsKey(command); + } + + /** + * Checks if a command is currently scheduled to run, but is not yet running. + * + * @param command the command to check + * @return true if the command is scheduled to run, false if not + */ + public boolean isScheduled(Command command) { + return onDeck.stream().anyMatch(state -> state.command() == command); + } + + /** + * Checks if a command is currently scheduled to run, or is already running. + * + * @param command the command to check + * @return true if the command is scheduled to run or is already running, false if not + */ + public boolean isScheduledOrRunning(Command command) { + return isScheduled(command) || isRunning(command); + } + + /** + * Gets the set of all currently running commands. Commands are returned in the order in which + * they were scheduled. The returned set is read-only. + * + * @return the currently running commands + */ + public Collection getRunningCommands() { + return Collections.unmodifiableSet(commandStates.keySet()); + } + + /** + * Gets all the currently running commands that require a particular resource. Commands are + * returned in the order in which they were scheduled. The returned list is read-only. + * + * @param resource the resource to get the commands for + * @return the currently running commands that require the resource. + */ + public List getRunningCommandsFor(RequireableResource resource) { + return commandStates.keySet().stream().filter(command -> command.requires(resource)).toList(); + } + + /** + * Cancels all currently running commands. Commands that are scheduled that haven't yet started + * will remain scheduled, and will start on the next call to {@link #run()}. + */ + public void cancelAll() { + // Remove scheduled children of running commands + onDeck.removeIf(s -> commandStates.containsKey(s.parent())); + + // Finally, remove running commands + commandStates.clear(); + } + + /** + * An event loop used by the scheduler to poll triggers that schedule or cancel commands. This + * event loop is always polled on every call to {@link #run()}. Custom event loops need to be + * bound to this one for synchronicity with the scheduler; however, they can always be polled + * manually before or after the call to {@link #run()}. + * + * @return the default event loop. + */ + public EventLoop getDefaultEventLoop() { + return eventLoop; + } + + /** For internal use. */ + public Collection getScheduledCommands() { + return onDeck.stream().map(CommandState::command).toList(); + } + + /** For internal use. */ + public Command getParentOf(Command command) { + var state = commandStates.get(command); + if (state == null) { + return null; + } + return state.parent(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java new file mode 100644 index 00000000000..567b8c79c90 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java @@ -0,0 +1,162 @@ +// 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.commandsv3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.ArrayList; +import java.util.HashSet; +import java.util.List; +import java.util.Set; +import java.util.function.BooleanSupplier; +import java.util.stream.Collectors; + +/** + * A sequence of commands that run one after another. Each successive command only starts after its + * predecessor completes execution. The priority of a sequence is equal to the highest priority of + * any of its commands. If all commands in the sequence are able to run while the robot is disabled, + * then the sequence itself will be allowed to run while the robot is disabled. + * + *

The sequence will own all resources required by all commands in the sequence for the + * entire duration of the sequence. This means that a resource owned by one command in the sequence, + * but not by a later one, will be uncommanded while that later command executes. + */ +public class Sequence implements Command { + private final String name; + private final List commands = new ArrayList<>(); + private final Set requirements = new HashSet<>(); + private final int priority; + private RobotDisabledBehavior robotDisabledBehavior; + + /** + * Creates a new command sequence. + * + * @param name the name of the sequence + * @param commands the commands to execute within the sequence + */ + public Sequence(String name, List commands) { + this.name = name; + this.commands.addAll(commands); + + for (var command : commands) { + this.requirements.addAll(command.requirements()); + } + + this.priority = + commands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); + + this.robotDisabledBehavior = RobotDisabledBehavior.RunWhileDisabled; + for (var command : commands) { + if (command.robotDisabledBehavior() == RobotDisabledBehavior.CancelWhileDisabled) { + this.robotDisabledBehavior = RobotDisabledBehavior.CancelWhileDisabled; + break; + } + } + } + + @Override + public void run(Coroutine coroutine) { + for (var command : commands) { + coroutine.await(command); + } + } + + @Override + public String name() { + return name; + } + + @Override + public Set requirements() { + return requirements; + } + + @Override + public int priority() { + return priority; + } + + @Override + public RobotDisabledBehavior robotDisabledBehavior() { + return robotDisabledBehavior; + } + + public static Builder builder() { + return new Builder(); + } + + public static Builder sequence(Command... commands) { + var builder = new Builder(); + for (var command : commands) { + builder.andThen(command); + } + return builder; + } + + public static Command of(Command... commands) { + return sequence(commands).withAutomaticName(); + } + + public static final class Builder { + private final List steps = new ArrayList<>(); + private BooleanSupplier endCondition = null; + + /** + * Adds a command to the sequence. + * + * @param next The next command in the sequence + * @return The builder object, for chaining + */ + public Builder andThen(Command next) { + requireNonNullParam(next, "next", "Sequence.Builder.andThen"); + + steps.add(next); + return this; + } + + /** + * Adds an end condition to the command group. If this condition is met before all required + * commands have completed, the group will exit early. If multiple end conditions are added + * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end + * condition added will be used and any previously configured condition will be overridden. + * + * @param condition The end condition for the group + * @return The builder object, for chaining + */ + public Builder until(BooleanSupplier endCondition) { + this.endCondition = endCondition; + return this; + } + + /** + * Creates the sequence command, giving it the specified name. + * + * @param name The name of the sequence command + * @return The built command + */ + public Command named(String name) { + var seq = new Sequence(name, steps); + if (endCondition != null) { + // No custom end condition, return the group as is + return seq; + } + + // We have a custom end condition, so we need to wrap the group in a race + return ParallelGroup.builder() + .optional(seq, Command.waitingFor(endCondition).named("Until Condition")) + .named(name); + } + + /** + * Creates the sequence command, giving it an automatically generated name based on the commands + * in the sequence. + * + * @return The built command + */ + public Command withAutomaticName() { + return named(steps.stream().map(Command::name).collect(Collectors.joining(" -> "))); + } + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java new file mode 100644 index 00000000000..2c42d1c6bea --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java @@ -0,0 +1,40 @@ +// 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.commandsv3; + +import static edu.wpi.first.units.Units.Seconds; +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.units.measure.Time; +import edu.wpi.first.wpilibj.Timer; +import java.util.Set; + +/** A command with no requirements that merely waits for a specified duration of time to elapse. */ +public class WaitCommand implements Command { + private final Time duration; + + public WaitCommand(Time duration) { + this.duration = requireNonNullParam(duration, "duration", "WaitCommand"); + } + + @Override + public void run(Coroutine coroutine) { + var timer = new Timer(); + timer.start(); + while (!timer.hasElapsed(duration.in(Seconds))) { + coroutine.yield(); + } + } + + @Override + public String name() { + return "Wait " + duration.in(Seconds) + " Seconds"; + } + + @Override + public Set requirements() { + return Set.of(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java new file mode 100644 index 00000000000..ceb1ede8ae9 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java @@ -0,0 +1,57 @@ +// 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.commandsv3.proto; + +import edu.wpi.first.util.protobuf.Protobuf; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import us.hebi.quickbuf.Descriptors; + +public class CommandProto implements Protobuf { + private final Scheduler scheduler; + + public CommandProto(Scheduler scheduler) { + this.scheduler = scheduler; + } + + @Override + public Class getTypeClass() { + return Command.class; + } + + @Override + public Descriptors.Descriptor getDescriptor() { + return ProtobufCommand.getDescriptor(); + } + + @Override + public ProtobufCommand createMessage() { + return ProtobufCommand.newInstance(); + } + + @Override + public Command unpack(ProtobufCommand msg) { + // Not possible. The command behavior is what really matters, and it cannot be serialized + throw new UnsupportedOperationException("Deserialization not supported"); + } + + @Override + public void pack(ProtobufCommand msg, Command value) { + // Use identityHashCode for ID fields. Object hashCode can be overridden and collide + msg.setId(System.identityHashCode(value)); + if (scheduler.getParentOf(value) instanceof Command parent) { + msg.setParentId(System.identityHashCode(parent)); + } + msg.setName(value.name()); + msg.setPriority(value.priority()); + + for (var requirement : value.requirements()) { + var rrp = new RequireableResourceProto(); + ProtobufRequireableResource requirementMessage = rrp.createMessage(); + rrp.pack(requirementMessage, requirement); + msg.addRequirements(requirementMessage); + } + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java new file mode 100644 index 00000000000..7a1206e0435 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java @@ -0,0 +1,670 @@ +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.wpilibj.commandsv3.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.RepeatedMessage; +import us.hebi.quickbuf.Utf8String; + +/** Protobuf type {@code ProtobufCommand} */ +@SuppressWarnings("hiding") +public final class ProtobufCommand extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** optional int32 priority = 4; */ + private int priority; + + /** optional uint32 id = 1; */ + private int id; + + /** optional uint32 parent_id = 2; */ + private int parentId; + + /** optional string name = 3; */ + private final Utf8String name = Utf8String.newEmptyInstance(); + + /** repeated .wpi.proto.ProtobufRequireableResource requirements = 5; */ + private final RepeatedMessage requirements = + RepeatedMessage.newEmptyInstance(ProtobufRequireableResource.getFactory()); + + private ProtobufCommand() {} + + /** + * @return a new empty instance of {@code ProtobufCommand} + */ + public static ProtobufCommand newInstance() { + return new ProtobufCommand(); + } + + /** + * optional int32 priority = 4; + * + * @return whether the priority field is set + */ + public boolean hasPriority() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional int32 priority = 4; + * + * @return this + */ + public ProtobufCommand clearPriority() { + bitField0_ &= ~0x00000001; + priority = 0; + return this; + } + + /** + * optional int32 priority = 4; + * + * @return the priority + */ + public int getPriority() { + return priority; + } + + /** + * optional int32 priority = 4; + * + * @param value the priority to set + * @return this + */ + public ProtobufCommand setPriority(final int value) { + bitField0_ |= 0x00000001; + priority = value; + return this; + } + + /** + * optional uint32 id = 1; + * + * @return whether the id field is set + */ + public boolean hasId() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional uint32 id = 1; + * + * @return this + */ + public ProtobufCommand clearId() { + bitField0_ &= ~0x00000002; + id = 0; + return this; + } + + /** + * optional uint32 id = 1; + * + * @return the id + */ + public int getId() { + return id; + } + + /** + * optional uint32 id = 1; + * + * @param value the id to set + * @return this + */ + public ProtobufCommand setId(final int value) { + bitField0_ |= 0x00000002; + id = value; + return this; + } + + /** + * optional uint32 parent_id = 2; + * + * @return whether the parentId field is set + */ + public boolean hasParentId() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional uint32 parent_id = 2; + * + * @return this + */ + public ProtobufCommand clearParentId() { + bitField0_ &= ~0x00000004; + parentId = 0; + return this; + } + + /** + * optional uint32 parent_id = 2; + * + * @return the parentId + */ + public int getParentId() { + return parentId; + } + + /** + * optional uint32 parent_id = 2; + * + * @param value the parentId to set + * @return this + */ + public ProtobufCommand setParentId(final int value) { + bitField0_ |= 0x00000004; + parentId = value; + return this; + } + + /** + * optional string name = 3; + * + * @return whether the name field is set + */ + public boolean hasName() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional string name = 3; + * + * @return this + */ + public ProtobufCommand clearName() { + bitField0_ &= ~0x00000008; + name.clear(); + return this; + } + + /** + * optional string name = 3; + * + * @return the name + */ + public String getName() { + return name.getString(); + } + + /** + * optional string name = 3; + * + * @return internal {@code Utf8String} representation of name for reading + */ + public Utf8String getNameBytes() { + return this.name; + } + + /** + * optional string name = 3; + * + * @return internal {@code Utf8String} representation of name for modifications + */ + public Utf8String getMutableNameBytes() { + bitField0_ |= 0x00000008; + return this.name; + } + + /** + * optional string name = 3; + * + * @param value the name to set + * @return this + */ + public ProtobufCommand setName(final CharSequence value) { + bitField0_ |= 0x00000008; + name.copyFrom(value); + return this; + } + + /** + * optional string name = 3; + * + * @param value the name to set + * @return this + */ + public ProtobufCommand setName(final Utf8String value) { + bitField0_ |= 0x00000008; + name.copyFrom(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * @return whether the requirements field is set + */ + public boolean hasRequirements() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * @return this + */ + public ProtobufCommand clearRequirements() { + bitField0_ &= ~0x00000010; + requirements.clear(); + return this; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method + * returns the internal storage object without modifying any has state. The returned object should + * not be modified and be treated as read-only. + * + *

Use {@link #getMutableRequirements()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getRequirements() { + return requirements; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method + * returns the internal storage object and sets the corresponding has state. The returned object + * will become part of this message and its contents may be modified as long as the has state is + * not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableRequirements() { + bitField0_ |= 0x00000010; + return requirements; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * @param value the requirements to add + * @return this + */ + public ProtobufCommand addRequirements(final ProtobufRequireableResource value) { + bitField0_ |= 0x00000010; + requirements.add(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * @param values the requirements to add + * @return this + */ + public ProtobufCommand addAllRequirements(final ProtobufRequireableResource... values) { + bitField0_ |= 0x00000010; + requirements.addAll(values); + return this; + } + + @Override + public ProtobufCommand copyFrom(final ProtobufCommand other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + priority = other.priority; + id = other.id; + parentId = other.parentId; + name.copyFrom(other.name); + requirements.copyFrom(other.requirements); + } + return this; + } + + @Override + public ProtobufCommand mergeFrom(final ProtobufCommand other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasPriority()) { + setPriority(other.priority); + } + if (other.hasId()) { + setId(other.id); + } + if (other.hasParentId()) { + setParentId(other.parentId); + } + if (other.hasName()) { + getMutableNameBytes().copyFrom(other.name); + } + if (other.hasRequirements()) { + getMutableRequirements().addAll(other.requirements); + } + return this; + } + + @Override + public ProtobufCommand clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + priority = 0; + id = 0; + parentId = 0; + name.clear(); + requirements.clear(); + return this; + } + + @Override + public ProtobufCommand clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + requirements.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufCommand)) { + return false; + } + ProtobufCommand other = (ProtobufCommand) o; + return bitField0_ == other.bitField0_ + && (!hasPriority() || priority == other.priority) + && (!hasId() || id == other.id) + && (!hasParentId() || parentId == other.parentId) + && (!hasName() || name.equals(other.name)) + && (!hasRequirements() || requirements.equals(other.requirements)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 32); + output.writeInt32NoTag(priority); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 8); + output.writeUInt32NoTag(id); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 16); + output.writeUInt32NoTag(parentId); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 26); + output.writeStringNoTag(name); + } + if ((bitField0_ & 0x00000010) != 0) { + for (int i = 0; i < requirements.length(); i++) { + output.writeRawByte((byte) 42); + output.writeMessageNoTag(requirements.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeInt32SizeNoTag(priority); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(id); + } + if ((bitField0_ & 0x00000004) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(parentId); + } + if ((bitField0_ & 0x00000008) != 0) { + size += 1 + ProtoSink.computeStringSizeNoTag(name); + } + if ((bitField0_ & 0x00000010) != 0) { + size += (1 * requirements.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(requirements); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 32: + { + // priority + priority = input.readInt32(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 8) { + break; + } + } + case 8: + { + // id + id = input.readUInt32(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 16) { + break; + } + } + case 16: + { + // parentId + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: + { + // name + input.readString(name); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 42) { + break; + } + } + case 42: + { + // requirements + tag = input.readRepeatedMessage(requirements, tag); + bitField0_ |= 0x00000010; + if (tag != 0) { + break; + } + } + case 0: + { + return this; + } + default: + { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeInt32(FieldNames.priority, priority); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeUInt32(FieldNames.id, id); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeUInt32(FieldNames.parentId, parentId); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeString(FieldNames.name, name); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRepeatedMessage(FieldNames.requirements, requirements); + } + output.endObject(); + } + + @Override + public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1165461084: + { + if (input.isAtField(FieldNames.priority)) { + if (!input.trySkipNullValue()) { + priority = input.readInt32(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3355: + { + if (input.isAtField(FieldNames.id)) { + if (!input.trySkipNullValue()) { + id = input.readUInt32(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 1175162725: + case 2070327504: + { + if (input.isAtField(FieldNames.parentId)) { + if (!input.trySkipNullValue()) { + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3373707: + { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1619874672: + { + if (input.isAtField(FieldNames.requirements)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(requirements); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + default: + { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufCommand clone() { + return new ProtobufCommand().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufCommand parseFrom(final byte[] data) throws InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), data).checkInitialized(); + } + + public static ProtobufCommand parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); + } + + public static ProtobufCommand parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufCommand messages + */ + public static MessageFactory getFactory() { + return ProtobufCommandFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Scheduler.wpi_proto_ProtobufCommand_descriptor; + } + + private enum ProtobufCommandFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufCommand create() { + return ProtobufCommand.newInstance(); + } + } + + /** Contains name constants used for serializing JSON */ + static class FieldNames { + static final FieldName priority = FieldName.forField("priority"); + + static final FieldName id = FieldName.forField("id"); + + static final FieldName parentId = FieldName.forField("parentId", "parent_id"); + + static final FieldName name = FieldName.forField("name"); + + static final FieldName requirements = FieldName.forField("requirements"); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java new file mode 100644 index 00000000000..c3ba80225a1 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java @@ -0,0 +1,302 @@ +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.wpilibj.commandsv3.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.Utf8String; + +/** Protobuf type {@code ProtobufRequireableResource} */ +@SuppressWarnings("hiding") +public final class ProtobufRequireableResource extends ProtoMessage + implements Cloneable { + private static final long serialVersionUID = 0L; + + /** optional string name = 1; */ + private final Utf8String name = Utf8String.newEmptyInstance(); + + private ProtobufRequireableResource() {} + + /** + * @return a new empty instance of {@code ProtobufRequireableResource} + */ + public static ProtobufRequireableResource newInstance() { + return new ProtobufRequireableResource(); + } + + /** + * optional string name = 1; + * + * @return whether the name field is set + */ + public boolean hasName() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional string name = 1; + * + * @return this + */ + public ProtobufRequireableResource clearName() { + bitField0_ &= ~0x00000001; + name.clear(); + return this; + } + + /** + * optional string name = 1; + * + * @return the name + */ + public String getName() { + return name.getString(); + } + + /** + * optional string name = 1; + * + * @return internal {@code Utf8String} representation of name for reading + */ + public Utf8String getNameBytes() { + return this.name; + } + + /** + * optional string name = 1; + * + * @return internal {@code Utf8String} representation of name for modifications + */ + public Utf8String getMutableNameBytes() { + bitField0_ |= 0x00000001; + return this.name; + } + + /** + * optional string name = 1; + * + * @param value the name to set + * @return this + */ + public ProtobufRequireableResource setName(final CharSequence value) { + bitField0_ |= 0x00000001; + name.copyFrom(value); + return this; + } + + /** + * optional string name = 1; + * + * @param value the name to set + * @return this + */ + public ProtobufRequireableResource setName(final Utf8String value) { + bitField0_ |= 0x00000001; + name.copyFrom(value); + return this; + } + + @Override + public ProtobufRequireableResource copyFrom(final ProtobufRequireableResource other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + name.copyFrom(other.name); + } + return this; + } + + @Override + public ProtobufRequireableResource mergeFrom(final ProtobufRequireableResource other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasName()) { + getMutableNameBytes().copyFrom(other.name); + } + return this; + } + + @Override + public ProtobufRequireableResource clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + return this; + } + + @Override + public ProtobufRequireableResource clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufRequireableResource)) { + return false; + } + ProtobufRequireableResource other = (ProtobufRequireableResource) o; + return bitField0_ == other.bitField0_ && (!hasName() || name.equals(other.name)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeStringNoTag(name); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeStringSizeNoTag(name); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufRequireableResource mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: + { + // name + input.readString(name); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: + { + return this; + } + default: + { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeString(FieldNames.name, name); + } + output.endObject(); + } + + @Override + public ProtobufRequireableResource mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3373707: + { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: + { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufRequireableResource clone() { + return new ProtobufRequireableResource().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufRequireableResource parseFrom(final byte[] data) + throws InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), data).checkInitialized(); + } + + public static ProtobufRequireableResource parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), input).checkInitialized(); + } + + public static ProtobufRequireableResource parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufRequireableResource messages + */ + public static MessageFactory getFactory() { + return ProtobufRequireableResourceFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Scheduler.wpi_proto_ProtobufRequireableResource_descriptor; + } + + private enum ProtobufRequireableResourceFactory + implements MessageFactory { + INSTANCE; + + @Override + public ProtobufRequireableResource create() { + return ProtobufRequireableResource.newInstance(); + } + } + + /** Contains name constants used for serializing JSON */ + static class FieldNames { + static final FieldName name = FieldName.forField("name"); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java new file mode 100644 index 00000000000..bee98f6bda4 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java @@ -0,0 +1,479 @@ +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.wpilibj.commandsv3.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.RepeatedMessage; + +/** Protobuf type {@code ProtobufScheduler} */ +@SuppressWarnings("hiding") +public final class ProtobufScheduler extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * + * + *

+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + */ + private final RepeatedMessage queuedCommands = + RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); + + /** repeated .wpi.proto.ProtobufCommand running_commands = 2; */ + private final RepeatedMessage runningCommands = + RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); + + private ProtobufScheduler() {} + + /** + * @return a new empty instance of {@code ProtobufScheduler} + */ + public static ProtobufScheduler newInstance() { + return new ProtobufScheduler(); + } + + /** + * + * + *
+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * @return whether the queuedCommands field is set + */ + public boolean hasQueuedCommands() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * + * + *
+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * @return this + */ + public ProtobufScheduler clearQueuedCommands() { + bitField0_ &= ~0x00000001; + queuedCommands.clear(); + return this; + } + + /** + * + * + *
+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; This method returns the + * internal storage object without modifying any has state. The returned object should not be + * modified and be treated as read-only. + * + *

Use {@link #getMutableQueuedCommands()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getQueuedCommands() { + return queuedCommands; + } + + /** + * + * + *

+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; This method returns the + * internal storage object and sets the corresponding has state. The returned object will become + * part of this message and its contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableQueuedCommands() { + bitField0_ |= 0x00000001; + return queuedCommands; + } + + /** + * + * + *
+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * @param value the queuedCommands to add + * @return this + */ + public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { + bitField0_ |= 0x00000001; + queuedCommands.add(value); + return this; + } + + /** + * + * + *
+   *  Note: commands are generally queued by triggers, which occurs immediately before they are
+   *  promoted and start running. Entries will only appear here when serializing a scheduler
+   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
+   * 
+ * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * @param values the queuedCommands to add + * @return this + */ + public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { + bitField0_ |= 0x00000001; + queuedCommands.addAll(values); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * @return whether the runningCommands field is set + */ + public boolean hasRunningCommands() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * @return this + */ + public ProtobufScheduler clearRunningCommands() { + bitField0_ &= ~0x00000002; + runningCommands.clear(); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; This method returns the + * internal storage object without modifying any has state. The returned object should not be + * modified and be treated as read-only. + * + *

Use {@link #getMutableRunningCommands()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getRunningCommands() { + return runningCommands; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; This method returns the + * internal storage object and sets the corresponding has state. The returned object will become + * part of this message and its contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableRunningCommands() { + bitField0_ |= 0x00000002; + return runningCommands; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * @param value the runningCommands to add + * @return this + */ + public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { + bitField0_ |= 0x00000002; + runningCommands.add(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * @param values the runningCommands to add + * @return this + */ + public ProtobufScheduler addAllRunningCommands(final ProtobufCommand... values) { + bitField0_ |= 0x00000002; + runningCommands.addAll(values); + return this; + } + + @Override + public ProtobufScheduler copyFrom(final ProtobufScheduler other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + queuedCommands.copyFrom(other.queuedCommands); + runningCommands.copyFrom(other.runningCommands); + } + return this; + } + + @Override + public ProtobufScheduler mergeFrom(final ProtobufScheduler other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasQueuedCommands()) { + getMutableQueuedCommands().addAll(other.queuedCommands); + } + if (other.hasRunningCommands()) { + getMutableRunningCommands().addAll(other.runningCommands); + } + return this; + } + + @Override + public ProtobufScheduler clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + queuedCommands.clear(); + runningCommands.clear(); + return this; + } + + @Override + public ProtobufScheduler clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + queuedCommands.clearQuick(); + runningCommands.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufScheduler)) { + return false; + } + ProtobufScheduler other = (ProtobufScheduler) o; + return bitField0_ == other.bitField0_ + && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) + && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < queuedCommands.length(); i++) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(queuedCommands.get(i)); + } + } + if ((bitField0_ & 0x00000002) != 0) { + for (int i = 0; i < runningCommands.length(); i++) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(runningCommands.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += + (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); + } + if ((bitField0_ & 0x00000002) != 0) { + size += + (1 * runningCommands.length()) + + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: + { + // queuedCommands + tag = input.readRepeatedMessage(queuedCommands, tag); + bitField0_ |= 0x00000001; + if (tag != 18) { + break; + } + } + case 18: + { + // runningCommands + tag = input.readRepeatedMessage(runningCommands, tag); + bitField0_ |= 0x00000002; + if (tag != 0) { + break; + } + } + case 0: + { + return this; + } + default: + { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedMessage(FieldNames.queuedCommands, queuedCommands); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRepeatedMessage(FieldNames.runningCommands, runningCommands); + } + output.endObject(); + } + + @Override + public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -167160549: + case -1904270380: + { + if (input.isAtField(FieldNames.queuedCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(queuedCommands); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1719052953: + case 1526672648: + { + if (input.isAtField(FieldNames.runningCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(runningCommands); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: + { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufScheduler clone() { + return new ProtobufScheduler().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufScheduler parseFrom(final byte[] data) + throws InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), data).checkInitialized(); + } + + public static ProtobufScheduler parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); + } + + public static ProtobufScheduler parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufScheduler messages + */ + public static MessageFactory getFactory() { + return ProtobufSchedulerFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Scheduler.wpi_proto_ProtobufScheduler_descriptor; + } + + private enum ProtobufSchedulerFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufScheduler create() { + return ProtobufScheduler.newInstance(); + } + } + + /** Contains name constants used for serializing JSON */ + static class FieldNames { + static final FieldName queuedCommands = FieldName.forField("queuedCommands", "queued_commands"); + + static final FieldName runningCommands = + FieldName.forField("runningCommands", "running_commands"); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java new file mode 100644 index 00000000000..6a80a3a5799 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java @@ -0,0 +1,37 @@ +// 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.commandsv3.proto; + +import edu.wpi.first.util.protobuf.Protobuf; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import us.hebi.quickbuf.Descriptors; + +public class RequireableResourceProto + implements Protobuf { + @Override + public Class getTypeClass() { + return RequireableResource.class; + } + + @Override + public Descriptors.Descriptor getDescriptor() { + return ProtobufRequireableResource.getDescriptor(); + } + + @Override + public ProtobufRequireableResource createMessage() { + return ProtobufRequireableResource.newInstance(); + } + + @Override + public RequireableResource unpack(ProtobufRequireableResource msg) { + throw new UnsupportedOperationException("Deserialization not supported"); + } + + @Override + public void pack(ProtobufRequireableResource msg, RequireableResource value) { + msg.setName(value.getName()); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java new file mode 100644 index 00000000000..9418ce027f1 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java @@ -0,0 +1,63 @@ +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.wpilibj.commandsv3.proto; + +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class Scheduler { + private static final RepeatedByte descriptorData = + ProtoUtil.decodeBase64( + 1691, + "Ciljb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5wcm90bxIJd3BpLnByb3RvIjEKG1By" + + "b3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZRISCgRuYW1lGAEgASgJUgRuYW1lIroBCg9Qcm90b2J1ZkNv" + + "bW1hbmQSDgoCaWQYASABKA1SAmlkEhsKCXBhcmVudF9pZBgCIAEoDVIIcGFyZW50SWQSEgoEbmFtZRgD" + + "IAEoCVIEbmFtZRIaCghwcmlvcml0eRgEIAEoBVIIcHJpb3JpdHkSSgoMcmVxdWlyZW1lbnRzGAUgAygL" + + "MiYud3BpLnByb3RvLlByb3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZVIMcmVxdWlyZW1lbnRzIp8BChFQ" + + "cm90b2J1ZlNjaGVkdWxlchJDCg9xdWV1ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9i" + + "dWZDb21tYW5kUg5xdWV1ZWRDb21tYW5kcxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnBy" + + "b3RvLlByb3RvYnVmQ29tbWFuZFIPcnVubmluZ0NvbW1hbmRzQioKJmVkdS53cGkuZmlyc3Qud3BpbGli" + + "ai5jb21tYW5kc3YzLnByb3RvUAFKnAkKBhIEAAAiAQoICgEMEgMAABIKCAoBAhIDAgASCggKAQgSAwQA" + + "PwoJCgIIARIDBAA/CggKAQgSAwUAIgoJCgIIChIDBQAiCrICCgIEABIEEAASATKlAgogTk9URTogYWxs" + + "b2NhdGlvbj1sYXp5bXNnIGlzIHJlcXVpcmVkIHdoZW4gZ2VuZXJhdGluZyB0aGUgSmF2YSBjbGFzc2Vz" + + "IGZvciB0aGlzIGZpbGUsCiAgICAgICBkdWUgdG8gdGhlIHJlY3Vyc2l2ZSBQcm90b2J1ZkNvbW1hbmQg" + + "c2NoZW1hCgphbGx3cGlsaWIgJCBwcm90b2MtcXVpY2tidWYgXAotLXF1aWNrYnVmX291dD1hbGxvY2F0" + + "aW9uPWxhenltc2csZ2VuX2Rlc2NyaXB0b3JzPXRydWU6Y29tbWFuZHN2My9zcmMvbWFpbi9qYXZhIFwK" + + "Y29tbWFuZHN2My9zcmMvbWFpbi9wcm90by9zY2hlZHVsZXIucHJvdG8KCgoKAwQAARIDEAgjCgsKBAQA" + + "AgASAxECEgoMCgUEAAIABRIDEQIICgwKBQQAAgABEgMRCQ0KDAoFBAACAAMSAxEQEQoKCgIEARIEFAAa" + + "AQoKCgMEAQESAxQIFwoLCgQEAQIAEgMVAhAKDAoFBAECAAUSAxUCCAoMCgUEAQIAARIDFQkLCgwKBQQB" + + "AgADEgMVDg8KCwoEBAECARIDFgIXCgwKBQQBAgEFEgMWAggKDAoFBAECAQESAxYJEgoMCgUEAQIBAxID" + + "FhUWCgsKBAQBAgISAxcCEgoMCgUEAQICBRIDFwIICgwKBQQBAgIBEgMXCQ0KDAoFBAECAgMSAxcQEQoL" + + "CgQEAQIDEgMYAhUKDAoFBAECAwUSAxgCBwoMCgUEAQIDARIDGAgQCgwKBQQBAgMDEgMYExQKCwoEBAEC", + "BBIDGQI4CgwKBQQBAgQEEgMZAgoKDAoFBAECBAYSAxkLJgoMCgUEAQIEARIDGSczCgwKBQQBAgQDEgMZ" + + "NjcKCgoCBAISBBwAIgEKCgoDBAIBEgMcCBkKjQIKBAQCAgASAyACLxr/ASBOb3RlOiBjb21tYW5kcyBh" + + "cmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2ggb2NjdXJzIGltbWVkaWF0ZWx5IGJl" + + "Zm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5pbmcuIEVudHJpZXMgd2lsbCBvbmx5" + + "IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVsZXIKIF9hZnRlcl8gbWFudWFsbHkg" + + "c2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxpbmcgc2NoZWR1bGVyLnJ1bigpCgoM" + + "CgUEAgIABBIDIAIKCgwKBQQCAgAGEgMgCxoKDAoFBAICAAESAyAbKgoMCgUEAgIAAxIDIC0uCgsKBAQC" + + "AgESAyECMAoMCgUEAgIBBBIDIQIKCgwKBQQCAgEGEgMhCxoKDAoFBAICAQESAyEbKwoMCgUEAgIBAxID" + + "IS4vYgZwcm90bzM="); + + static final Descriptors.FileDescriptor descriptor = + Descriptors.FileDescriptor.internalBuildGeneratedFileFrom( + "commandsv3/src/main/proto/scheduler.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufRequireableResource_descriptor = + descriptor.internalContainedType( + 56, 49, "ProtobufRequireableResource", "wpi.proto.ProtobufRequireableResource"); + + static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = + descriptor.internalContainedType(108, 186, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + + static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = + descriptor.internalContainedType( + 297, 159, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java new file mode 100644 index 00000000000..a7aabb156b0 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java @@ -0,0 +1,48 @@ +// 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.commandsv3.proto; + +import edu.wpi.first.util.protobuf.Protobuf; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import us.hebi.quickbuf.Descriptors; + +public class SchedulerProto implements Protobuf { + @Override + public Class getTypeClass() { + return Scheduler.class; + } + + @Override + public Descriptors.Descriptor getDescriptor() { + return ProtobufScheduler.getDescriptor(); + } + + @Override + public ProtobufScheduler createMessage() { + return ProtobufScheduler.newInstance(); + } + + @Override + public Scheduler unpack(ProtobufScheduler msg) { + throw new UnsupportedOperationException("Deserialization not supported"); + } + + @Override + public void pack(ProtobufScheduler msg, Scheduler scheduler) { + var cp = new CommandProto(scheduler); + + for (var command : scheduler.getScheduledCommands()) { + ProtobufCommand commandMessage = cp.createMessage(); + cp.pack(commandMessage, command); + msg.addQueuedCommands(commandMessage); + } + + for (var command : scheduler.getRunningCommands()) { + ProtobufCommand commandMessage = cp.createMessage(); + cp.pack(commandMessage, command); + msg.addRunningCommands(commandMessage); + } + } +} diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/scheduler.proto new file mode 100644 index 00000000000..e05e3e40308 --- /dev/null +++ b/commandsv3/src/main/proto/scheduler.proto @@ -0,0 +1,32 @@ +syntax = "proto3"; + +package wpi.proto; + +option java_package = "edu.wpi.first.wpilibj.commandsv3.proto"; +option java_multiple_files = true; + +/* +allwpilib $ protoc-quickbuf \ + --quickbuf_out=gen_descriptors=true:commandsv3/src/main/java \ + commandsv3/src/main/proto/scheduler.proto + */ + +message ProtobufRequireableResource { + string name = 1; +} + +message ProtobufCommand { + uint32 id = 1; + optional uint32 parent_id = 2; + string name = 3; + int32 priority = 4; + repeated ProtobufRequireableResource requirements = 5; +} + +message ProtobufScheduler { + // Note: commands are generally queued by triggers, which occurs immediately before they are + // promoted and start running. Entries will only appear here when serializing a scheduler + // _after_ manually scheduling a command but _before_ calling scheduler.run() + repeated ProtobufCommand queued_commands = 1; + repeated ProtobufCommand running_commands = 2; +} diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java new file mode 100644 index 00000000000..4ae2767c4f5 --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java @@ -0,0 +1,235 @@ +// 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.commandsv3; + +import static org.junit.jupiter.api.Assertions.*; + +import java.util.List; +import java.util.concurrent.atomic.AtomicInteger; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class ParallelGroupTest { + private Scheduler scheduler; + + @BeforeEach + void setup() { + scheduler = new Scheduler(); + } + + @Test + void parallelAll() { + var r1 = new RequireableResource("R1", scheduler); + var r2 = new RequireableResource("R2", scheduler); + + var c1Count = new AtomicInteger(0); + var c2Count = new AtomicInteger(0); + + var c1 = + r1.run( + (coroutine) -> { + for (int i = 0; i < 5; i++) { + coroutine.yield(); + c1Count.incrementAndGet(); + } + }) + .named("C1"); + var c2 = + r2.run( + (coroutine) -> { + for (int i = 0; i < 10; i++) { + coroutine.yield(); + c2Count.incrementAndGet(); + } + }) + .named("C2"); + + var parallel = new ParallelGroup("Parallel", List.of(c1, c2), List.of(c1, c2)); + scheduler.schedule(parallel); + + // First call to run() should schedule and start the commands + scheduler.run(); + assertTrue(scheduler.isRunning(parallel)); + assertTrue(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + + // Next call to run() should start them + for (int i = 1; i < 5; i++) { + scheduler.run(); + assertTrue(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + assertEquals(i, c1Count.get()); + assertEquals(i, c2Count.get()); + } + // c1 should finish after 5 iterations; c2 should continue for another 5 + for (int i = 5; i < 10; i++) { + scheduler.run(); + assertFalse(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + assertEquals(5, c1Count.get()); + assertEquals(i, c2Count.get()); + } + // one final run() should unschedule the c2 command + scheduler.run(); + assertFalse(scheduler.isRunning(c1)); + assertFalse(scheduler.isRunning(c2)); + + // the next run should complete the group + scheduler.run(); + assertFalse(scheduler.isRunning(parallel)); + + // and final counts should be 5 and 10 + assertEquals(5, c1Count.get()); + assertEquals(10, c2Count.get()); + } + + @Test + void race() { + var r1 = new RequireableResource("R1", scheduler); + var r2 = new RequireableResource("R2", scheduler); + + var c1Count = new AtomicInteger(0); + var c2Count = new AtomicInteger(0); + + var c1 = + r1.run( + (coroutine) -> { + for (int i = 0; i < 5; i++) { + coroutine.yield(); + c1Count.incrementAndGet(); + } + }) + .named("C1"); + var c2 = + r2.run( + (coroutine) -> { + for (int i = 0; i < 10; i++) { + coroutine.yield(); + c2Count.incrementAndGet(); + } + }) + .named("C2"); + + var race = new ParallelGroup("Race", List.of(c1, c2), List.of()); + scheduler.schedule(race); + + // First call to run() should schedule the commands + scheduler.run(); + assertTrue(scheduler.isRunning(race)); + assertTrue(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + + for (int i = 1; i < 5; i++) { + scheduler.run(); + assertTrue(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + assertEquals(i, c1Count.get()); + assertEquals(i, c2Count.get()); + } + scheduler.run(); // complete c1 + assertTrue(scheduler.isRunning(race)); + assertFalse(scheduler.isRunning(c1)); + assertTrue(scheduler.isRunning(c2)); + + scheduler.run(); // complete parallel and cleanup + assertFalse(scheduler.isRunning(race)); + assertFalse(scheduler.isRunning(c2)); + + // and final counts should be 5 and 5 + assertEquals(5, c1Count.get()); + assertEquals(5, c2Count.get()); + } + + @Test + void nested() { + var resource = new RequireableResource("Resource", scheduler); + + var count = new AtomicInteger(0); + + var command = + resource + .run( + (coroutine) -> { + for (int i = 0; i < 5; i++) { + coroutine.yield(); + count.incrementAndGet(); + } + }) + .named("Command"); + + var inner = ParallelGroup.all(command).named("Inner"); + var outer = ParallelGroup.all(inner).named("Outer"); + + // Scheduling: Outer group should be on deck + scheduler.schedule(outer); + assertTrue(scheduler.isScheduled(outer)); + assertFalse(scheduler.isScheduledOrRunning(inner)); + assertFalse(scheduler.isScheduledOrRunning(command)); + + // First run: Inner group and command should both be scheduled and running + scheduler.run(); + assertTrue(scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(scheduler.isRunning(inner), "Inner group should be running"); + assertTrue(scheduler.isRunning(command), "Command should be running"); + assertEquals(0, count.get()); + + // Runs 2 through 5: Outer and inner should both be running while the command runs + for (int i = 1; i < 5; i++) { + scheduler.run(); + assertTrue(scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(scheduler.isRunning(inner), "Inner group should be running"); + assertTrue(scheduler.isRunning(command), "Command should be running (" + i + ")"); + assertEquals(i, count.get()); + } + + // Run 6: Command should have completed naturally + scheduler.run(); + assertTrue(scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(scheduler.isRunning(inner), "Inner group should be running"); + assertFalse(scheduler.isRunning(command), "Command should have completed"); + + // Run 7: Having seen the command complete, inner group should exit + scheduler.run(); + assertTrue(scheduler.isRunning(outer), "Outer group should be running"); + assertFalse(scheduler.isRunning(inner), "Inner group should have completed"); + assertFalse(scheduler.isRunning(command), "Command should have completed"); + + // Run 8: Having seen the inner group complete, outer group should now exit + scheduler.run(); + assertFalse(scheduler.isRunning(outer), "Outer group should be running"); + assertFalse(scheduler.isRunning(inner), "Inner group should have completed"); + assertFalse(scheduler.isRunning(command), "Command should have completed"); + } + + @Test + void automaticNameRace() { + var a = Command.noRequirements((coroutine) -> {}).named("A"); + var b = Command.noRequirements((coroutine) -> {}).named("B"); + var c = Command.noRequirements((coroutine) -> {}).named("C"); + + var group = ParallelGroup.builder().optional(a, b, c).withAutomaticName(); + assertEquals("(A | B | C)", group.name()); + } + + @Test + void automaticNameAll() { + var a = Command.noRequirements((coroutine) -> {}).named("A"); + var b = Command.noRequirements((coroutine) -> {}).named("B"); + var c = Command.noRequirements((coroutine) -> {}).named("C"); + + var group = ParallelGroup.builder().requiring(a, b, c).withAutomaticName(); + assertEquals("(A & B & C)", group.name()); + } + + @Test + void automaticNameDeadline() { + var a = Command.noRequirements((coroutine) -> {}).named("A"); + var b = Command.noRequirements((coroutine) -> {}).named("B"); + var c = Command.noRequirements((coroutine) -> {}).named("C"); + + var group = ParallelGroup.builder().requiring(a).optional(b, c).withAutomaticName(); + assertEquals("[(A) * (B | C)]", group.name()); + } +} diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java new file mode 100644 index 00000000000..c95691983db --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java @@ -0,0 +1,668 @@ +// 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.commandsv3; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertInstanceOf; +import static org.junit.jupiter.api.Assertions.assertThrowsExactly; +import static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; + +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; +import java.util.Set; +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; +import org.junit.jupiter.api.Timeout; + +@Timeout(5) +class SchedulerTest { + private Scheduler scheduler; + + @BeforeEach + void setup() { + scheduler = new Scheduler(); + } + + @Test + void basic() { + var enabled = new AtomicBoolean(false); + var ran = new AtomicBoolean(false); + var command = + Command.noRequirements( + (coroutine) -> { + do { + coroutine.yield(); + } while (!enabled.get()); + ran.set(true); + }) + .named("Basic Command"); + + scheduler.schedule(command); + scheduler.run(); + assertTrue(scheduler.isRunning(command), "Command should be running after being scheduled"); + + enabled.set(true); + scheduler.run(); + if (scheduler.isRunning(command)) { + fail("Command should no longer be running after awaiting its completion"); + } + + assertTrue(ran.get()); + } + + @Test + void higherPriorityCancels() { + var subsystem = new RequireableResource("Subsystem", scheduler); + + var lower = new PriorityCommand(-1000, subsystem); + var higher = new PriorityCommand(+1000, subsystem); + + scheduler.schedule(lower); + scheduler.run(); + assertTrue(scheduler.isRunning(lower)); + + scheduler.schedule(higher); + scheduler.run(); + assertTrue(scheduler.isRunning(higher)); + assertFalse(scheduler.isRunning(lower)); + } + + @Test + void lowerPriorityDoesNotCancel() { + var subsystem = new RequireableResource("Subsystem", scheduler); + + var lower = new PriorityCommand(-1000, subsystem); + var higher = new PriorityCommand(+1000, subsystem); + + scheduler.schedule(higher); + scheduler.run(); + assertTrue(scheduler.isRunning(higher)); + + scheduler.schedule(lower); + scheduler.run(); + if (!scheduler.isRunning(higher)) { + fail("Higher priority command should still be running"); + } + if (scheduler.isRunning(lower)) { + fail("Lower priority command should not be running"); + } + } + + @Test + void samePriorityCancels() { + var subsystem = new RequireableResource("Subsystem", scheduler); + + var first = new PriorityCommand(512, subsystem); + var second = new PriorityCommand(512, subsystem); + + scheduler.schedule(first); + scheduler.run(); + assertTrue(scheduler.isRunning(first)); + + scheduler.schedule(second); + scheduler.run(); + assertTrue(scheduler.isRunning(second), "New command should be running"); + assertFalse(scheduler.isRunning(first), "Old command should be canceled"); + } + + @Test + void atomicity() { + var resource = + new RequireableResource("X", scheduler) { + int x = 0; + }; + + // Launch 100 commands that each call `x++` 500 times. + // If commands run on different threads, the lack of atomic + // operations or locks will mean the final number will be + // less than the expected 50,000 + int numCommands = 100; + int iterations = 500; + + for (int cmdCount = 0; cmdCount < numCommands; cmdCount++) { + var command = + Command.noRequirements( + (coroutine) -> { + for (int i = 0; i < iterations; i++) { + coroutine.yield(); + resource.x++; + } + }) + .named("CountCommand[" + cmdCount + "]"); + + scheduler.schedule(command); + } + + for (int i = 0; i < iterations; i++) { + scheduler.run(); + } + scheduler.run(); + + assertEquals(numCommands * iterations, resource.x); + } + + @Test + void errorDetection() { + var resource = new RequireableResource("X", scheduler); + + var command = + resource + .run( + (coroutine) -> { + throw new RuntimeException("The exception"); + }) + .named("Bad Behavior"); + + scheduler.schedule(command); + + try { + scheduler.run(); + fail("An exception should have been thrown"); + } catch (CommandExecutionException e) { + if (e.getCommand() != command) { + fail("Expected command " + command + ", but was " + e.getCommand()); + } + + var cause = e.getCause(); + if (cause instanceof RuntimeException re) { + assertEquals("The exception", re.getMessage()); + } else { + fail( + "Expected cause to be a RuntimeException with message 'The exception', but was " + + cause); + } + } catch (Throwable t) { + fail("Expected a CommandExecutionException to be thrown, but got " + t); + } + } + + @Test + void runResource() { + var example = + new RequireableResource("Counting", scheduler) { + int x = 0; + }; + + Command countToTen = + example + .run( + (coroutine) -> { + example.x = 0; + for (int i = 0; i < 10; i++) { + coroutine.yield(); + example.x++; + } + }) + .named("Count To Ten"); + + scheduler.schedule(countToTen); + for (int i = 0; i < 10; i++) { + scheduler.run(); + } + scheduler.run(); + + assertEquals(10, example.x); + } + + @Test + void cancelOnInterruptDoesNotResume() { + var count = new AtomicInteger(0); + + var resource = new RequireableResource("Resource", scheduler); + + var interrupter = + Command.requiring(resource) + .executing((coroutine) -> {}) + .withPriority(2) + .named("Interrupter"); + + var canceledCommand = + Command.requiring(resource) + .executing( + (coroutine) -> { + count.set(1); + coroutine.yield(); + count.set(2); + }) + .withPriority(1) + .named("Cancel By Default"); + + scheduler.schedule(canceledCommand); + scheduler.run(); + + scheduler.schedule(interrupter); + scheduler.run(); + assertEquals(1, count.get()); // the second "set" call should not have run + } + + @Test + void scheduleOverDefaultDoesNotRescheduleDefault() { + var count = new AtomicInteger(0); + + var resource = new RequireableResource("Resource", scheduler); + var defaultCmd = + resource + .run( + (coroutine) -> { + while (true) { + count.incrementAndGet(); + coroutine.yield(); + } + }) + .withPriority(-1) + .named("Default Command"); + + var newerCmd = resource.run((coroutine) -> {}).named("Newer Command"); + resource.setDefaultCommand(defaultCmd); + scheduler.run(); + assertTrue(scheduler.isRunning(defaultCmd), "Default command should be running"); + + scheduler.schedule(newerCmd); + scheduler.run(); + assertFalse(scheduler.isRunning(defaultCmd), "Default command should have been interrupted"); + assertEquals(1, count.get(), "Default command should have run once"); + + scheduler.run(); + assertTrue(scheduler.isRunning(defaultCmd)); + } + + @Test + void cancelAllCancelsAll() { + var commands = new ArrayList(10); + for (int i = 1; i <= 10; i++) { + commands.add(Command.noRequirements(Coroutine::yield).named("Command " + i)); + } + commands.forEach(scheduler::schedule); + scheduler.run(); + scheduler.cancelAll(); + for (Command command : commands) { + if (scheduler.isRunning(command)) { + fail(command.name() + " was not canceled by cancelAll()"); + } + } + } + + @Test + void cancelAllStartsDefaults() { + var resources = new ArrayList(10); + for (int i = 1; i <= 10; i++) { + resources.add(new RequireableResource("System " + i, scheduler)); + } + + var command = + new CommandBuilder().requiring(resources).executing(Coroutine::yield).named("Big Command"); + + // Scheduling the command should evict the on-deck default commands + scheduler.schedule(command); + + // Then running should get it into the set of running commands + scheduler.run(); + + // Cancelling should clear out the set of running commands + scheduler.cancelAll(); + + // Then ticking the scheduler once to fully remove the command and schedule the defaults + scheduler.run(); + + // Then one more tick to start running the scheduled defaults + scheduler.run(); + + if (scheduler.isRunning(command)) { + System.err.println(scheduler.getRunningCommands()); + fail(command.name() + " was not canceled by cancelAll()"); + } + + for (var resource : resources) { + var runningCommands = scheduler.getRunningCommandsFor(resource); + assertEquals( + 1, + runningCommands.size(), + "Resource " + resource + " should have exactly one running command"); + assertInstanceOf( + IdleCommand.class, + runningCommands.getFirst(), + "Resource " + resource + " is not running the default command"); + } + } + + @Test + void cancelDeeplyNestedCompositions() { + Command root = + Command.noRequirements( + (co) -> { + co.await( + Command.noRequirements( + (co2) -> { + co2.await( + Command.noRequirements( + (co3) -> { + co3.await( + Command.noRequirements(Coroutine::park) + .named("Park")); + }) + .named("C3")); + }) + .named("C2")); + }) + .named("Root"); + + scheduler.schedule(root); + + scheduler.run(); + assertEquals(4, scheduler.getRunningCommands().size()); + + scheduler.cancel(root); + assertEquals(0, scheduler.getRunningCommands().size()); + } + + @Test + void compositionsDoNotSelfCancel() { + var res = new RequireableResource("The Resource", scheduler); + var group = + res.run( + (co) -> { + co.await( + res.run( + (co2) -> { + co2.await( + res.run( + (co3) -> { + co3.await(res.run(Coroutine::park).named("Park")); + }) + .named("C3")); + }) + .named("C2")); + }) + .named("Group"); + + scheduler.schedule(group); + scheduler.run(); + assertEquals(4, scheduler.getRunningCommands().size()); + assertTrue(scheduler.isRunning(group)); + } + + @Test + void compositionsDoNotNeedRequirements() { + var r1 = new RequireableResource("R1", scheduler); + var r2 = new RequireableResource("r2", scheduler); + + // the group has no requirements, but can schedule child commands that do + var group = + Command.noRequirements( + (co) -> { + co.awaitAll( + r1.run(Coroutine::park).named("R1 Command"), + r2.run(Coroutine::park).named("R2 Command")); + }) + .named("Composition"); + + scheduler.schedule(group); + scheduler.run(); // start r1 and r2 commands + assertEquals(3, scheduler.getRunningCommands().size()); + } + + @Test + void compositionsCannotAwaitConflictingCommands() { + var res = new RequireableResource("The Resource", scheduler); + + var group = + Command.noRequirements( + (co) -> { + co.awaitAll( + res.run(Coroutine::park).named("First"), + res.run(Coroutine::park).named("Second")); + }) + .named("Group"); + + scheduler.schedule(group); + + // Running should attempt to schedule multiple conflicting commands + try { + scheduler.run(); + fail("An exception should have been thrown"); + } catch (CommandExecutionException e) { + if (e.getCause() instanceof IllegalArgumentException iae) { + assertEquals( + "Command Second requires resources that are already used by First. Both require The Resource", + iae.getMessage()); + } else { + fail("Unexpected exception: " + e); + } + } + } + + @Test + void doesNotRunOnCancelWhenInterruptingOnDeck() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = resource.run(Coroutine::yield).named("Interrupter"); + scheduler.schedule(cmd); + scheduler.schedule(interrupter); + scheduler.run(); + + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void doesNotRunOnCancelWhenCancellingOnDeck() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + scheduler.schedule(cmd); + // cancelling before calling .run() + scheduler.cancel(cmd); + scheduler.run(); + + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void runsOnCancelWhenInterruptingCommand() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = resource.run(Coroutine::park).named("Interrupter"); + scheduler.schedule(cmd); + scheduler.run(); + scheduler.schedule(interrupter); + scheduler.run(); + + assertTrue(ran.get(), "onCancel should have run!"); + } + + @Test + void doesNotRunOnCancelWhenCompleting() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + scheduler.schedule(cmd); + scheduler.run(); + scheduler.run(); + + assertFalse(scheduler.isScheduledOrRunning(cmd)); + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void runsOnCancelWhenCancelling() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + scheduler.schedule(cmd); + scheduler.run(); + scheduler.cancel(cmd); + + assertTrue(ran.get(), "onCancel should have run!"); + } + + @Test + void runsOnCancelWhenCancellingParent() { + var ran = new AtomicBoolean(false); + + var resource = new RequireableResource("The Resource", scheduler); + var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + + var group = new Sequence("Seq", Collections.singletonList(cmd)); + scheduler.schedule(group); + scheduler.run(); + scheduler.cancel(group); + + assertTrue(ran.get(), "onCancel should have run!"); + } + + @Test + void sideloadThrowingException() { + scheduler.sideload( + co -> { + throw new RuntimeException("Bang!"); + }); + + // An exception raised in a sideload function should bubble up + assertEquals("Bang!", assertThrowsExactly(RuntimeException.class, scheduler::run).getMessage()); + } + + @Test + void nestedResources() { + var superstructure = + new RequireableResource("Superstructure", scheduler) { + private final RequireableResource elevator = + new RequireableResource("Elevator", scheduler); + private final RequireableResource arm = new RequireableResource("Arm", scheduler); + + public Command superCommand() { + return run(co -> { + co.await(elevator.run(Coroutine::park).named("Elevator Subcommand")); + co.await(arm.run(Coroutine::park).named("Arm Subcommand")); + }) + .named("Super Command"); + } + }; + + scheduler.schedule(superstructure.superCommand()); + scheduler.run(); + assertEquals( + List.of(superstructure.arm.getDefaultCommand()), + superstructure.arm.getRunningCommands(), + "Arm should only be running its default command"); + + // Scheduling something that requires an in-use inner resource cancels the outer command + scheduler.schedule(superstructure.elevator.run(Coroutine::park).named("Conflict")); + + scheduler.run(); // schedules the default superstructure command + scheduler.run(); // starts running the default superstructure command + assertEquals(List.of(superstructure.getDefaultCommand()), superstructure.getRunningCommands()); + } + + @Test + void protobuf() { + var res = new RequireableResource("The Resource", scheduler); + var parkCommand = res.run(Coroutine::park).named("Park"); + var c3Command = res.run((co) -> co.await(parkCommand)).named("C3"); + var c2Command = res.run((co) -> co.await(c3Command)).named("C2"); + var group = res.run((co) -> co.await(c2Command)).named("Group"); + + scheduler.schedule(group); + scheduler.run(); + + var scheduledCommand1 = Command.noRequirements(Coroutine::park).named("Command 1"); + var scheduledCommand2 = Command.noRequirements(Coroutine::park).named("Command 2"); + scheduler.schedule(scheduledCommand1); + scheduler.schedule(scheduledCommand2); + + var message = Scheduler.proto.createMessage(); + Scheduler.proto.pack(message, scheduler); + var messageJson = message.toString(); + assertEquals( + """ + { + "queuedCommands": [{ + "priority": 0, + "id": %s, + "name": "Command 1" + }, { + "priority": 0, + "id": %s, + "name": "Command 2" + }], + "runningCommands": [{ + "priority": 0, + "id": %s, + "name": "Group", + "requirements": [{ + "name": "The Resource" + }] + }, { + "priority": 0, + "id": %s, + "parentId": %s, + "name": "C2", + "requirements": [{ + "name": "The Resource" + }] + }, { + "priority": 0, + "id": %s, + "parentId": %s, + "name": "C3", + "requirements": [{ + "name": "The Resource" + }] + }, { + "priority": 0, + "id": %s, + "parentId": %s, + "name": "Park", + "requirements": [{ + "name": "The Resource" + }] + }] + }""" + .formatted( + System.identityHashCode(scheduledCommand1), // id + System.identityHashCode(scheduledCommand2), // id + System.identityHashCode(group), // id + System.identityHashCode(c2Command), // id + System.identityHashCode(group), // parent + System.identityHashCode(c3Command), // id + System.identityHashCode(c2Command), // parent + System.identityHashCode(parkCommand), // id + System.identityHashCode(c3Command) // parent + ), + messageJson); + } + + record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { + @Override + public void run(Coroutine coroutine) { + coroutine.park(); + } + + @Override + public Set requirements() { + return Set.of(subsystems); + } + + @Override + public String name() { + return toString(); + } + + @Override + public String toString() { + return "PriorityCommand[priority=" + priority + ", subsystems=" + Set.of(subsystems) + "]"; + } + } +} diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java new file mode 100644 index 00000000000..6694486b76d --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java @@ -0,0 +1,84 @@ +// 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.commandsv3; + +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import java.util.List; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class SequenceTest { + private Scheduler scheduler; + + @BeforeEach + void setup() { + scheduler = new Scheduler(); + } + + @Test + void single() { + var command = Command.noRequirements(Coroutine::yield).named("The Command"); + + var sequence = new Sequence("The Sequence", List.of(command)); + scheduler.schedule(sequence); + + // First run - the composed command is scheduled and starts + scheduler.run(); + assertTrue(scheduler.isRunning(sequence)); + assertTrue(scheduler.isRunning(command)); + + // Second run - the composed command completes + scheduler.run(); + assertTrue(scheduler.isRunning(sequence)); + assertFalse(scheduler.isRunning(command)); + + // Third run - sequence sees the composed command is done and completes + scheduler.run(); + assertFalse(scheduler.isRunning(sequence)); + assertFalse(scheduler.isRunning(command)); + } + + @Test + void twoCommands() { + var c1 = Command.noRequirements(Coroutine::yield).named("C1"); + var c2 = Command.noRequirements(Coroutine::yield).named("C2"); + + var sequence = new Sequence("C1 > C2", List.of(c1, c2)); + scheduler.schedule(sequence); + + // First run - c1 is scheduled and starts + scheduler.run(); + assertTrue(scheduler.isRunning(sequence), "Sequence should be running"); + assertTrue(scheduler.isRunning(c1), "Starting the sequence should start the first command"); + assertFalse( + scheduler.isScheduledOrRunning(c2), + "The second command should still be pending completion of the first command"); + + // Second run - c1 completes + scheduler.run(); + assertTrue(scheduler.isRunning(sequence)); + assertFalse(scheduler.isRunning(c1), "First command should have completed"); + assertFalse( + scheduler.isScheduledOrRunning(c2), "Second command should not start in the same cycle"); + + // Third run - c2 is scheduled and starts + scheduler.run(); + assertTrue(scheduler.isRunning(sequence)); + assertTrue(scheduler.isRunning(c2), "Second command should have started"); + + // Fourth run - c2 completes + scheduler.run(); + assertTrue(scheduler.isRunning(sequence)); + assertFalse(scheduler.isRunning(c2), "Second command should have completed"); + + // Fifth run - sequence completes + scheduler.run(); + assertFalse(scheduler.isRunning(sequence), "Sequence should have completed"); + assertFalse(scheduler.isRunning(c1), "First command should have stopped"); + assertFalse(scheduler.isRunning(c2), "Second command should have stopped"); + } +} From 66828247fae19c7f3ea0777d88c8b9680b94d00e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:15:53 -0400 Subject: [PATCH 004/153] Add command joysticks and buttons Mirroring the existing v2 classes Trigger is additionally refactored to make binding types more explicit instead of relying on anonymous inner classes to track state --- .../commandsv3/button/CommandGenericHID.java | 254 +++++++++++ .../commandsv3/button/CommandJoystick.java | 246 +++++++++++ .../button/CommandPS4Controller.java | 388 +++++++++++++++++ .../button/CommandPS5Controller.java | 388 +++++++++++++++++ .../button/CommandStadiaController.java | 404 ++++++++++++++++++ .../button/CommandXboxController.java | 392 +++++++++++++++++ .../commandsv3/button/InternalButton.java | 60 +++ .../commandsv3/button/JoystickButton.java | 23 + .../commandsv3/button/NetworkButton.java | 65 +++ .../wpilibj/commandsv3/button/POVButton.java | 34 ++ .../commandsv3/button/RobotModeTriggers.java | 52 +++ .../wpilibj/commandsv3/button/Trigger.java | 334 +++++++++++++++ .../commandsv3/button/TriggerTest.java | 130 ++++++ 13 files changed, 2770 insertions(+) create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java create mode 100644 commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java new file mode 100644 index 00000000000..70d3ac670f3 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java @@ -0,0 +1,254 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link GenericHID} with {@link Trigger} factories for command-based. + * + * @see GenericHID + */ +public class CommandGenericHID { + private final GenericHID m_hid; + + /** + * Construct an instance of a device. + * + * @param port The port index on the Driver Station that the device is plugged into. + */ + public CommandGenericHID(int port) { + m_hid = new GenericHID(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + public GenericHID getHID() { + return m_hid; + } + + /** + * Constructs an event instance around this button's digital signal. + * + * @param button the button index + * @return an event instance representing the button's digital signal attached to the {@link + * Scheduler#getInstance() default scheduler button scheduler}. + * @see #button(int, Scheduler) + */ + public Trigger button(int button) { + return this.button(button, Scheduler.getInstance()); + } + + /** + * Constructs an event instance around this button's digital signal. + * + * @param button the button index + * @param scheduler the scheduler instance to attach the event to. + * @return an event instance representing the button's digital signal attached to the given + * scheduler. + */ + public Trigger button(int button, Scheduler scheduler) { + return new Trigger(scheduler, () -> m_hid.getRawButton(button)); + } + + /** + * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, + * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * + *

The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, + * upper-left is 315). + * + * @param angle POV angle in degrees, or -1 for the center / not pressed. + * @return a Trigger instance based around this angle of a POV on the HID. + */ + public Trigger pov(int angle) { + return pov(0, angle, Scheduler.getInstance()); + } + + /** + * Constructs a Trigger instance based around this angle of a POV on the HID. + * + *

The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, + * upper-left is 315). + * + * @param pov index of the POV to read (starting at 0). Defaults to 0. + * @param angle POV angle in degrees, or -1 for the center / not pressed. + * @param scheduler the scheduler instance to attach the event to. Defaults to {@link + * Scheduler#getInstance() the default command scheduler button scheduler}. + * @return a Trigger instance based around this angle of a POV on the HID. + */ + public Trigger pov(int pov, int angle, Scheduler scheduler) { + return new Trigger(scheduler, () -> m_hid.getPOV(pov) == angle); + } + + /** + * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV + * on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * scheduler}. + * + * @return a Trigger instance based around the 0 degree angle of a POV on the HID. + */ + public Trigger povUp() { + return pov(0); + } + + /** + * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index + * 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler + * button scheduler}. + * + * @return a Trigger instance based around the 45 degree angle of a POV on the HID. + */ + public Trigger povUpRight() { + return pov(45); + } + + /** + * Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0) + * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * scheduler}. + * + * @return a Trigger instance based around the 90 degree angle of a POV on the HID. + */ + public Trigger povRight() { + return pov(90); + } + + /** + * Constructs a Trigger instance based around the 135 degree angle (right down) of the default + * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * scheduler button scheduler}. + * + * @return a Trigger instance based around the 135 degree angle of a POV on the HID. + */ + public Trigger povDownRight() { + return pov(135); + } + + /** + * Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0) + * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * scheduler}. + * + * @return a Trigger instance based around the 180 degree angle of a POV on the HID. + */ + public Trigger povDown() { + return pov(180); + } + + /** + * Constructs a Trigger instance based around the 225 degree angle (down left) of the default + * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * scheduler button scheduler}. + * + * @return a Trigger instance based around the 225 degree angle of a POV on the HID. + */ + public Trigger povDownLeft() { + return pov(225); + } + + /** + * Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0) + * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * scheduler}. + * + * @return a Trigger instance based around the 270 degree angle of a POV on the HID. + */ + public Trigger povLeft() { + return pov(270); + } + + /** + * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index + * 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler + * button scheduler}. + * + * @return a Trigger instance based around the 315 degree angle of a POV on the HID. + */ + public Trigger povUpLeft() { + return pov(315); + } + + /** + * Constructs a Trigger instance based around the center (not pressed) position of the default + * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * scheduler button scheduler}. + * + * @return a Trigger instance based around the center position of a POV on the HID. + */ + public Trigger povCenter() { + return pov(-1); + } + + /** + * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, + * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value below which this trigger should return true. + * @return a Trigger instance that is true when the axis value is less than the provided + * threshold. + */ + public Trigger axisLessThan(int axis, double threshold) { + return axisLessThan(axis, threshold, Scheduler.getInstance()); + } + + /** + * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, + * attached to the given scheduler. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value below which this trigger should return true. + * @param scheduler the scheduler instance to attach the trigger to + * @return a Trigger instance that is true when the axis value is less than the provided + * threshold. + */ + public Trigger axisLessThan(int axis, double threshold, Scheduler scheduler) { + return new Trigger( + scheduler, m_hid.axisLessThan(axis, threshold, scheduler.getDefaultEventLoop())); + } + + /** + * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, + * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value above which this trigger should return true. + * @return a Trigger instance that is true when the axis value is greater than the provided + * threshold. + */ + public Trigger axisGreaterThan(int axis, double threshold) { + return axisGreaterThan(axis, threshold, Scheduler.getInstance()); + } + + /** + * Constructs a Trigger instance that is true when the axis value is greater than {@code + * threshold}, attached to the given scheduler. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value above which this trigger should return true. + * @param scheduler the scheduler instance to attach the trigger to. + * @return a Trigger instance that is true when the axis value is greater than the provided + * threshold. + */ + public Trigger axisGreaterThan(int axis, double threshold, Scheduler scheduler) { + return new Trigger( + scheduler, m_hid.axisGreaterThan(axis, threshold, scheduler.getDefaultEventLoop())); + } + + /** + * Get the value of the axis. + * + * @param axis The axis to read, starting at 0. + * @return The value of the axis. + */ + public double getRawAxis(int axis) { + return m_hid.getRawAxis(axis); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java new file mode 100644 index 00000000000..a921159dfeb --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java @@ -0,0 +1,246 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link Joystick} with {@link Trigger} factories for command-based. + * + * @see Joystick + */ +public class CommandJoystick extends CommandGenericHID { + private final Joystick m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandJoystick(int port) { + super(port); + m_hid = new Joystick(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public Joystick getHID() { + return m_hid; + } + + /** + * Constructs an event instance around the trigger button's digital signal. + * + * @return an event instance representing the trigger button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #trigger(Scheduler) + */ + public Trigger trigger() { + return trigger(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the trigger button's digital signal. + * + * @param scheduler the scheduler instance to attach the event to. + * @return an event instance representing the trigger button's digital signal attached to the + * given scheduler. + */ + public Trigger trigger(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.trigger(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the top button's digital signal. + * + * @return an event instance representing the top button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #top(Scheduler) + */ + public Trigger top() { + return top(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the top button's digital signal. + * + * @param scheduler the scheduler instance to attach the event to. + * @return an event instance representing the top button's digital signal attached to the given + * scheduler. + */ + public Trigger top(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.top(scheduler.getDefaultEventLoop())); + } + + /** + * Set the channel associated with the X axis. + * + * @param channel The channel to set the axis to. + */ + public void setXChannel(int channel) { + m_hid.setXChannel(channel); + } + + /** + * Set the channel associated with the Y axis. + * + * @param channel The channel to set the axis to. + */ + public void setYChannel(int channel) { + m_hid.setYChannel(channel); + } + + /** + * Set the channel associated with the Z axis. + * + * @param channel The channel to set the axis to. + */ + public void setZChannel(int channel) { + m_hid.setZChannel(channel); + } + + /** + * Set the channel associated with the throttle axis. + * + * @param channel The channel to set the axis to. + */ + public void setThrottleChannel(int channel) { + m_hid.setThrottleChannel(channel); + } + + /** + * Set the channel associated with the twist axis. + * + * @param channel The channel to set the axis to. + */ + public void setTwistChannel(int channel) { + m_hid.setTwistChannel(channel); + } + + /** + * Get the channel currently associated with the X axis. + * + * @return The channel for the axis. + */ + public int getXChannel() { + return m_hid.getXChannel(); + } + + /** + * Get the channel currently associated with the Y axis. + * + * @return The channel for the axis. + */ + public int getYChannel() { + return m_hid.getYChannel(); + } + + /** + * Get the channel currently associated with the Z axis. + * + * @return The channel for the axis. + */ + public int getZChannel() { + return m_hid.getZChannel(); + } + + /** + * Get the channel currently associated with the twist axis. + * + * @return The channel for the axis. + */ + public int getTwistChannel() { + return m_hid.getTwistChannel(); + } + + /** + * Get the channel currently associated with the throttle axis. + * + * @return The channel for the axis. + */ + public int getThrottleChannel() { + return m_hid.getThrottleChannel(); + } + + /** + * Get the x position of the HID. + * + * @return the x position + */ + public double getX() { + return m_hid.getX(); + } + + /** + * Get the y position of the HID. + * + * @return the y position + */ + public double getY() { + return m_hid.getY(); + } + + /** + * Get the z position of the HID. + * + * @return the z position + */ + public double getZ() { + return m_hid.getZ(); + } + + /** + * Get the twist value of the current joystick. This depends on the mapping of the joystick + * connected to the current port. + * + * @return The Twist value of the joystick. + */ + public double getTwist() { + return m_hid.getTwist(); + } + + /** + * Get the throttle value of the current joystick. This depends on the mapping of the joystick + * connected to the current port. + * + * @return The Throttle value of the joystick. + */ + public double getThrottle() { + return m_hid.getThrottle(); + } + + /** + * Get the magnitude of the direction vector formed by the joystick's current position relative to + * its origin. + * + * @return The magnitude of the direction vector + */ + public double getMagnitude() { + return m_hid.getMagnitude(); + } + + /** + * Get the direction of the vector formed by the joystick and its origin in radians. + * + * @return The direction of the vector in radians + */ + public double getDirectionRadians() { + return m_hid.getDirectionRadians(); + } + + /** + * Get the direction of the vector formed by the joystick and its origin in degrees. + * + * @return The direction of the vector in degrees + */ + public double getDirectionDegrees() { + return m_hid.getDirectionDegrees(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java new file mode 100644 index 00000000000..6d50ed70a9a --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java @@ -0,0 +1,388 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.PS4Controller; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link PS4Controller} with {@link Trigger} factories for command-based. + * + * @see PS4Controller + */ +@SuppressWarnings("MethodName") +public class CommandPS4Controller extends CommandGenericHID { + private final PS4Controller m_hid; + + /** + * Construct an instance of a device. + * + * @param port The port index on the Driver Station that the device is plugged into. + */ + public CommandPS4Controller(int port) { + super(port); + m_hid = new PS4Controller(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public PS4Controller getHID() { + return m_hid; + } + + /** + * Constructs an event instance around the L2 button's digital signal. + * + * @return an event instance representing the L2 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L2() { + return L2(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L2 button's digital signal. + * + * @param scheduler the event scheduler instance to attach the event to. + * @return an event instance representing the L2 button's digital signal attached to the given + * scheduler. + */ + public Trigger L2(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L2(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R2 button's digital signal. + * + * @return an event instance representing the R2 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R2() { + return R2(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R2 button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the R2 button's digital signal attached to the given + * loop. + */ + public Trigger R2(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R2(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the L1 button's digital signal. + * + * @return an event instance representing the L1 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L1() { + return L1(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L1 button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the L1 button's digital signal attached to the given + * loop. + */ + public Trigger L1(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L1(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R1 button's digital signal. + * + * @return an event instance representing the R1 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R1() { + return R1(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R1 button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the R1 button's digital signal attached to the given + * loop. + */ + public Trigger R1(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R1(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the L3 button's digital signal. + * + * @return an event instance representing the L3 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L3() { + return L3(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L3 button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the L3 button's digital signal attached to the given + * loop. + */ + public Trigger L3(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L3(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R3 button's digital signal. + * + * @return an event instance representing the R3 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R3() { + return R3(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R3 button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the R3 button's digital signal attached to the given + * loop. + */ + public Trigger R3(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R3(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the square button's digital signal. + * + * @return an event instance representing the square button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger square() { + return square(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the square button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the square button's digital signal attached to the given + * loop. + */ + public Trigger square(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.square(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the cross button's digital signal. + * + * @return an event instance representing the cross button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger cross() { + return cross(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the cross button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the cross button's digital signal attached to the given + * loop. + */ + public Trigger cross(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.cross(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the triangle button's digital signal. + * + * @return an event instance representing the triangle button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger triangle() { + return triangle(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the triangle button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the triangle button's digital signal attached to the + * given loop. + */ + public Trigger triangle(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.triangle(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the circle button's digital signal. + * + * @return an event instance representing the circle button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger circle() { + return circle(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the circle button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the circle button's digital signal attached to the given + * loop. + */ + public Trigger circle(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.circle(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the share button's digital signal. + * + * @return an event instance representing the share button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger share() { + return share(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the share button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the share button's digital signal attached to the given + * loop. + */ + public Trigger share(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.share(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the PS button's digital signal. + * + * @return an event instance representing the PS button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger PS() { + return PS(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the PS button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the PS button's digital signal attached to the given + * loop. + */ + public Trigger PS(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.PS(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the options button's digital signal. + * + * @return an event instance representing the options button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger options() { + return options(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the options button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the options button's digital signal attached to the + * given loop. + */ + public Trigger options(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.options(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the touchpad's digital signal. + * + * @return an event instance representing the touchpad's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger touchpad() { + return touchpad(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the touchpad's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the touchpad's digital signal attached to the given + * loop. + */ + public Trigger touchpad(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.touchpad(scheduler.getDefaultEventLoop())); + } + + /** + * Get the X axis value of left side of the controller. + * + * @return the axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. + * + * @return the axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. + * + * @return the axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. + * + * @return the axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the L2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as + * opposed to the usual [-1, 1]. + * + * @return the axis value. + */ + public double getL2Axis() { + return m_hid.getL2Axis(); + } + + /** + * Get the R2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as + * opposed to the usual [-1, 1]. + * + * @return the axis value. + */ + public double getR2Axis() { + return m_hid.getR2Axis(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java new file mode 100644 index 00000000000..5897fc324b9 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java @@ -0,0 +1,388 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.PS5Controller; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link PS5Controller} with {@link Trigger} factories for command-based. + * + * @see PS5Controller + */ +@SuppressWarnings("MethodName") +public class CommandPS5Controller extends CommandGenericHID { + private final PS5Controller m_hid; + + /** + * Construct an instance of a device. + * + * @param port The port index on the Driver Station that the device is plugged into. + */ + public CommandPS5Controller(int port) { + super(port); + m_hid = new PS5Controller(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public PS5Controller getHID() { + return m_hid; + } + + /** + * Constructs an event instance around the L2 button's digital signal. + * + * @return an event instance representing the L2 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L2() { + return L2(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the L2 button's digital signal attached to the given + * loop. + */ + public Trigger L2(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L2(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R2 button's digital signal. + * + * @return an event instance representing the R2 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R2() { + return R2(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the R2 button's digital signal attached to the given + * loop. + */ + public Trigger R2(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R2(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the L1 button's digital signal. + * + * @return an event instance representing the L1 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L1() { + return L1(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the L1 button's digital signal attached to the given + * loop. + */ + public Trigger L1(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L1(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R1 button's digital signal. + * + * @return an event instance representing the R1 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R1() { + return R1(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the R1 button's digital signal attached to the given + * loop. + */ + public Trigger R1(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R1(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the L3 button's digital signal. + * + * @return an event instance representing the L3 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger L3() { + return L3(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the L3 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the L3 button's digital signal attached to the given + * loop. + */ + public Trigger L3(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.L3(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the R3 button's digital signal. + * + * @return an event instance representing the R3 button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger R3() { + return R3(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the R3 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the R3 button's digital signal attached to the given + * loop. + */ + public Trigger R3(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.R3(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the square button's digital signal. + * + * @return an event instance representing the square button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger square() { + return square(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the square button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the square button's digital signal attached to the given + * loop. + */ + public Trigger square(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.square(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the cross button's digital signal. + * + * @return an event instance representing the cross button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger cross() { + return cross(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the cross button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the cross button's digital signal attached to the given + * loop. + */ + public Trigger cross(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.cross(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the triangle button's digital signal. + * + * @return an event instance representing the triangle button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger triangle() { + return triangle(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the triangle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the triangle button's digital signal attached to the + * given loop. + */ + public Trigger triangle(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.triangle(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the circle button's digital signal. + * + * @return an event instance representing the circle button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger circle() { + return circle(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the circle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the circle button's digital signal attached to the given + * loop. + */ + public Trigger circle(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.circle(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the create button's digital signal. + * + * @return an event instance representing the create button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger create() { + return create(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the create button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the create button's digital signal attached to the given + * loop. + */ + public Trigger create(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.create(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the PS button's digital signal. + * + * @return an event instance representing the PS button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger PS() { + return PS(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the PS button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the PS button's digital signal attached to the given + * loop. + */ + public Trigger PS(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.PS(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the options button's digital signal. + * + * @return an event instance representing the options button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger options() { + return options(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the options button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the options button's digital signal attached to the + * given loop. + */ + public Trigger options(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.options(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the touchpad's digital signal. + * + * @return an event instance representing the touchpad's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger touchpad() { + return touchpad(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the touchpad's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the touchpad's digital signal attached to the given + * loop. + */ + public Trigger touchpad(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.touchpad(scheduler.getDefaultEventLoop())); + } + + /** + * Get the X axis value of left side of the controller. + * + * @return the axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. + * + * @return the axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. + * + * @return the axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. + * + * @return the axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the L2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as + * opposed to the usual [-1, 1]. + * + * @return the axis value. + */ + public double getL2Axis() { + return m_hid.getL2Axis(); + } + + /** + * Get the R2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as + * opposed to the usual [-1, 1]. + * + * @return the axis value. + */ + public double getR2Axis() { + return m_hid.getR2Axis(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java new file mode 100644 index 00000000000..0ec634eb97b --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java @@ -0,0 +1,404 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.StadiaController; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link StadiaController} with {@link Trigger} factories for command-based. + * + * @see StadiaController + */ +@SuppressWarnings("MethodName") +public class CommandStadiaController extends CommandGenericHID { + private final StadiaController m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandStadiaController(int port) { + super(port); + m_hid = new StadiaController(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public StadiaController getHID() { + return m_hid; + } + + /** + * Constructs an event instance around the left bumper's digital signal. + * + * @return an event instance representing the left bumper's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftBumper(EventLoop) + */ + public Trigger leftBumper() { + return leftBumper(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the left bumper's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the right bumper's digital signal attached to the given + * loop. + */ + public Trigger leftBumper(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftBumper(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the right bumper's digital signal. + * + * @return an event instance representing the right bumper's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightBumper(EventLoop) + */ + public Trigger rightBumper() { + return rightBumper(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the right bumper's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the left bumper's digital signal attached to the given + * loop. + */ + public Trigger rightBumper(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightBumper(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the left stick button's digital signal. + * + * @return an event instance representing the left stick button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftStick(EventLoop) + */ + public Trigger leftStick() { + return leftStick(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the left stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the left stick button's digital signal attached to the + * given loop. + */ + public Trigger leftStick(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftStick(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the right stick button's digital signal. + * + * @return an event instance representing the right stick button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightStick(EventLoop) + */ + public Trigger rightStick() { + return rightStick(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the right stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the right stick button's digital signal attached to the + * given loop. + */ + public Trigger rightStick(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightStick(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the right trigger button's digital signal. + * + * @return an event instance representing the right trigger button's digital signal attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightTrigger(EventLoop) + */ + public Trigger rightTrigger() { + return rightTrigger(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the right trigger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the right trigger button's digital signal attached to + * the given loop. + */ + public Trigger rightTrigger(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightTrigger(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the left trigger button's digital signal. + * + * @return an event instance representing the left trigger button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftTrigger(EventLoop) + */ + public Trigger leftTrigger() { + return leftTrigger(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the left trigger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the left trigger button's digital signal attached to the + * given loop. + */ + public Trigger leftTrigger(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftTrigger(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the A button's digital signal. + * + * @return an event instance representing the A button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #a(EventLoop) + */ + public Trigger a() { + return a(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the A button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the A button's digital signal attached to the given + * loop. + */ + public Trigger a(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.a(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the B button's digital signal. + * + * @return an event instance representing the B button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #b(EventLoop) + */ + public Trigger b() { + return b(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the B button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the B button's digital signal attached to the given + * loop. + */ + public Trigger b(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.b(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the X button's digital signal. + * + * @return an event instance representing the X button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #x(EventLoop) + */ + public Trigger x() { + return x(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the X button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the X button's digital signal attached to the given + * loop. + */ + public Trigger x(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.x(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the Y button's digital signal. + * + * @return an event instance representing the Y button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #y(EventLoop) + */ + public Trigger y() { + return y(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the Y button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the Y button's digital signal attached to the given + * loop. + */ + public Trigger y(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.y(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the ellipses button's digital signal. + * + * @return an event instance representing the ellipses button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #ellipses(EventLoop) + */ + public Trigger ellipses() { + return ellipses(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the ellipses button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the ellipses button's digital signal attached to the + * given loop. + */ + public Trigger ellipses(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.ellipses(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the stadia button's digital signal. + * + * @return an event instance representing the stadia button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #stadia(EventLoop) + */ + public Trigger stadia() { + return stadia(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the stadia button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the stadia button's digital signal attached to the given + * loop. + */ + public Trigger stadia(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.stadia(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the google button's digital signal. + * + * @return an event instance representing the google button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #google(EventLoop) + */ + public Trigger google() { + return google(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the google button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the google button's digital signal attached to the given + * loop. + */ + public Trigger google(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.google(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the frame button's digital signal. + * + * @return an event instance representing the frame button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #frame(EventLoop) + */ + public Trigger frame() { + return frame(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the frame button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the frame button's digital signal attached to the given + * loop. + */ + public Trigger frame(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.frame(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the hamburger button's digital signal. + * + * @return an event instance representing the hamburger button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #hamburger(EventLoop) + */ + public Trigger hamburger() { + return hamburger(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the hamburger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the hamburger button's digital signal attached to the + * given loop. + */ + public Trigger hamburger(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.hamburger(scheduler.getDefaultEventLoop())); + } + + /** + * Get the X axis value of left side of the controller. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java new file mode 100644 index 00000000000..c2b05d76156 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java @@ -0,0 +1,392 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * A version of {@link XboxController} with {@link Trigger} factories for command-based. + * + * @see XboxController + */ +@SuppressWarnings("MethodName") +public class CommandXboxController extends CommandGenericHID { + private final XboxController m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandXboxController(int port) { + super(port); + m_hid = new XboxController(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public XboxController getHID() { + return m_hid; + } + + /** + * Constructs an event instance around the left bumper's digital signal. + * + * @return an event instance representing the left bumper's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftBumper(Scheduler) + */ + public Trigger leftBumper() { + return leftBumper(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the left bumper's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the right bumper's digital signal attached to the given + * loop. + */ + public Trigger leftBumper(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftBumper(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the right bumper's digital signal. + * + * @return an event instance representing the right bumper's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightBumper(Scheduler) + */ + public Trigger rightBumper() { + return rightBumper(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the right bumper's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the left bumper's digital signal attached to the given + * loop. + */ + public Trigger rightBumper(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightBumper(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the left stick button's digital signal. + * + * @return an event instance representing the left stick button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftStick(Scheduler) + */ + public Trigger leftStick() { + return leftStick(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the left stick button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the left stick button's digital signal attached to the + * given loop. + */ + public Trigger leftStick(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftStick(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the right stick button's digital signal. + * + * @return an event instance representing the right stick button's digital signal attached to the + * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightStick(Scheduler) + */ + public Trigger rightStick() { + return rightStick(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the right stick button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the right stick button's digital signal attached to the + * given loop. + */ + public Trigger rightStick(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightStick(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the A button's digital signal. + * + * @return an event instance representing the A button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #a(Scheduler) + */ + public Trigger a() { + return a(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the A button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the A button's digital signal attached to the given + * loop. + */ + public Trigger a(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.a(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the B button's digital signal. + * + * @return an event instance representing the B button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #b(Scheduler) + */ + public Trigger b() { + return b(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the B button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the B button's digital signal attached to the given + * loop. + */ + public Trigger b(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.b(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the X button's digital signal. + * + * @return an event instance representing the X button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #x(Scheduler) + */ + public Trigger x() { + return x(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the X button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the X button's digital signal attached to the given + * loop. + */ + public Trigger x(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.x(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the Y button's digital signal. + * + * @return an event instance representing the Y button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #y(Scheduler) + */ + public Trigger y() { + return y(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the Y button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the Y button's digital signal attached to the given + * loop. + */ + public Trigger y(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.y(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the start button's digital signal. + * + * @return an event instance representing the start button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #start(Scheduler) + */ + public Trigger start() { + return start(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the start button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the start button's digital signal attached to the given + * loop. + */ + public Trigger start(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.start(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs an event instance around the back button's digital signal. + * + * @return an event instance representing the back button's digital signal attached to the {@link + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #back(Scheduler) + */ + public Trigger back() { + return back(Scheduler.getInstance()); + } + + /** + * Constructs an event instance around the back button's digital signal. + * + * @param scheduler the event loop instance to attach the event to. + * @return an event instance representing the back button's digital signal attached to the given + * loop. + */ + public Trigger back(Scheduler scheduler) { + return new Trigger(scheduler, m_hid.back(scheduler.getDefaultEventLoop())); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger + * will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @param scheduler the event loop instance to attach the Trigger to. + * @return a Trigger instance that is true when the left trigger's axis exceeds the provided + * threshold, attached to the given event loop + */ + public Trigger leftTrigger(double threshold, Scheduler scheduler) { + return new Trigger(scheduler, m_hid.leftTrigger(threshold, scheduler.getDefaultEventLoop())); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger + * will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @return a Trigger instance that is true when the left trigger's axis exceeds the provided + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler button + * loop}. + */ + public Trigger leftTrigger(double threshold) { + return leftTrigger(threshold, Scheduler.getInstance()); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger + * will be true when the axis value is greater than 0.5. + * + * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger leftTrigger() { + return leftTrigger(0.5); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger + * will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @param scheduler the event loop instance to attach the Trigger to. + * @return a Trigger instance that is true when the right trigger's axis exceeds the provided + * threshold, attached to the given event loop + */ + public Trigger rightTrigger(double threshold, Scheduler scheduler) { + return new Trigger(scheduler, m_hid.rightTrigger(threshold, scheduler.getDefaultEventLoop())); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger + * will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @return a Trigger instance that is true when the right trigger's axis exceeds the provided + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler button + * loop}. + */ + public Trigger rightTrigger(double threshold) { + return rightTrigger(threshold, Scheduler.getInstance()); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger + * will be true when the axis value is greater than 0.5. + * + * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger rightTrigger() { + return rightTrigger(0.5); + } + + /** + * Get the X axis value of left side of the controller. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the left trigger (LT) axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getLeftTriggerAxis() { + return m_hid.getLeftTriggerAxis(); + } + + /** + * Get the right trigger (RT) axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getRightTriggerAxis() { + return m_hid.getRightTriggerAxis(); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java new file mode 100644 index 00000000000..71cbff8c9af --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java @@ -0,0 +1,60 @@ +// 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.commandsv3.button; + +import java.util.concurrent.atomic.AtomicBoolean; + +/** + * This class is intended to be used within a program. The programmer can manually set its value. + * Also includes a setting for whether it should invert its value. + */ +public class InternalButton extends Trigger { + // need to be references, so they can be mutated after being captured in the constructor. + private final AtomicBoolean m_pressed; + private final AtomicBoolean 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) { + this(new AtomicBoolean(), new AtomicBoolean(inverted)); + } + + /* + * Mock constructor so the AtomicBoolean objects can be constructed before the super + * constructor invocation. + */ + private InternalButton(AtomicBoolean state, AtomicBoolean inverted) { + super(() -> state.get() != inverted.get()); + this.m_pressed = state; + this.m_inverted = inverted; + } + + /** + * Sets whether to invert button state. + * + * @param inverted Whether button state should be inverted. + */ + public void setInverted(boolean inverted) { + m_inverted.set(inverted); + } + + /** + * Sets whether button is pressed. + * + * @param pressed Whether button is pressed. + */ + public void setPressed(boolean pressed) { + m_pressed.set(pressed); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java new file mode 100644 index 00000000000..ec90ce6d180 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java @@ -0,0 +1,23 @@ +// 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.commandsv3.button; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.wpilibj.GenericHID; + +/** A {@link Trigger} that gets its state from a {@link GenericHID}. */ +public class JoystickButton extends Trigger { + /** + * Creates 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) { + super(() -> joystick.getRawButton(buttonNumber)); + requireNonNullParam(joystick, "joystick", "JoystickButton"); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java new file mode 100644 index 00000000000..d3b9e447cf3 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java @@ -0,0 +1,65 @@ +// 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.commandsv3.button; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.networktables.BooleanSubscriber; +import edu.wpi.first.networktables.BooleanTopic; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableInstance; + +/** A {@link Trigger} that uses a {@link NetworkTable} boolean field. */ +public class NetworkButton extends Trigger { + /** + * Creates a NetworkButton that commands can be bound to. + * + * @param topic The boolean topic that contains the value. + */ + public NetworkButton(BooleanTopic topic) { + this(topic.subscribe(false)); + } + + /** + * Creates a NetworkButton that commands can be bound to. + * + * @param sub The boolean subscriber that provides the value. + */ + public NetworkButton(BooleanSubscriber sub) { + super(() -> sub.getTopic().getInstance().isConnected() && sub.get()); + requireNonNullParam(sub, "sub", "NetworkButton"); + } + + /** + * Creates a NetworkButton that commands can be bound to. + * + * @param table The table where the networktable value is located. + * @param field The field that is the value. + */ + public NetworkButton(NetworkTable table, String field) { + this(table.getBooleanTopic(field)); + } + + /** + * Creates a NetworkButton that commands can be bound to. + * + * @param table The table where the networktable value is located. + * @param field The field that is the value. + */ + public NetworkButton(String table, String field) { + this(NetworkTableInstance.getDefault(), table, field); + } + + /** + * Creates a NetworkButton that commands can be bound to. + * + * @param inst The NetworkTable instance to use + * @param table The table where the networktable value is located. + * @param field The field that is the value. + */ + public NetworkButton(NetworkTableInstance inst, String table, String field) { + this(inst.getTable(table), field); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java new file mode 100644 index 00000000000..c29202eb628 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java @@ -0,0 +1,34 @@ +// 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.commandsv3.button; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.wpilibj.GenericHID; + +/** A {@link Trigger} that gets its state from a POV on a {@link GenericHID}. */ +public class POVButton extends Trigger { + /** + * 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) { + super(() -> joystick.getPOV(povNumber) == angle); + requireNonNullParam(joystick, "joystick", "POVButton"); + } + + /** + * 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); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java new file mode 100644 index 00000000000..5f28e793e56 --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java @@ -0,0 +1,52 @@ +// 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.commandsv3.button; + +import edu.wpi.first.wpilibj.DriverStation; + +/** + * A class containing static {@link Trigger} factories for running callbacks when the robot mode + * changes. + */ +public final class RobotModeTriggers { + // Utility class + private RobotModeTriggers() {} + + /** + * Returns a trigger that is true when the robot is enabled in autonomous mode. + * + * @return A trigger that is true when the robot is enabled in autonomous mode. + */ + public static Trigger autonomous() { + return new Trigger(DriverStation::isAutonomousEnabled); + } + + /** + * Returns a trigger that is true when the robot is enabled in teleop mode. + * + * @return A trigger that is true when the robot is enabled in teleop mode. + */ + public static Trigger teleop() { + return new Trigger(DriverStation::isTeleopEnabled); + } + + /** + * Returns a trigger that is true when the robot is disabled. + * + * @return A trigger that is true when the robot is disabled. + */ + public static Trigger disabled() { + return new Trigger(DriverStation::isDisabled); + } + + /** + * Returns a trigger that is true when the robot is enabled in test mode. + * + * @return A trigger that is true when the robot is enabled in test mode. + */ + public static Trigger test() { + return new Trigger(DriverStation::isTestEnabled); + } +} diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java new file mode 100644 index 00000000000..0f078612f9d --- /dev/null +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java @@ -0,0 +1,334 @@ +// 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.commandsv3.button; + +import static edu.wpi.first.units.Units.Seconds; +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import edu.wpi.first.math.filter.Debouncer; +import edu.wpi.first.units.measure.Time; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import edu.wpi.first.wpilibj.event.EventLoop; +import java.util.ArrayList; +import java.util.EnumMap; +import java.util.List; +import java.util.Map; +import java.util.function.BooleanSupplier; + +/** + * This class provides an easy way to link commands to conditions. + * + *

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. + * + *

Triggers can easily be composed for advanced functionality using the {@link + * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators. + */ +public class Trigger implements BooleanSupplier { + private final BooleanSupplier m_condition; + private final EventLoop m_loop; + private final Scheduler scheduler; + private Signal m_previousSignal = null; + private final Map> m_bindings = new EnumMap<>(BindingType.class); + private final Runnable m_eventLoopCallback = this::poll; + + /** + * Represents the state of a signal: high or low. Used instead of a boolean for nullity on the + * first run, when the previous signal value is undefined and unknown. + */ + private enum Signal { + /** The signal is high. */ + HIGH, + /** The signal is low. */ + LOW + } + + private enum BindingType { + /** + * Schedules (forks) a command on a rising edge signal. The command will run until it completes + * or is interrupted by another command requiring the same resources. + */ + SCHEDULE_ON_RISING_EDGE, + /** + * Schedules (forks) a command on a falling edge signal. The command will run until it completes + * or is interrupted by another command requiring the same resources. + */ + SCHEDULE_ON_FALLING_EDGE, + /** + * Schedules (forks) a command on a rising edge signal. If the command is still running on the + * next rising edge, it will be cancelled then; otherwise, it will be scheduled again. + */ + TOGGLE_ON_RISING_EDGE, + /** + * Schedules (forks) a command on a falling edge signal. If the command is still running on the + * next falling edge, it will be cancelled then; otherwise, it will be scheduled again. + */ + TOGGLE_ON_FALLING_EDGE, + /** + * Schedules a command on a rising edge signal. If the command is still running on the next + * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which + * would allow it to continue to run. + */ + RUN_WHILE_HIGH, + /** + * Schedules a command on a falling edge signal. If the command is still running on the next + * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which + * would allow it to continue to run. + */ + RUN_WHILE_LOW + } + + public Trigger(Scheduler scheduler, BooleanSupplier condition) { + this.scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger"); + this.m_loop = scheduler.getDefaultEventLoop(); + this.m_condition = requireNonNullParam(condition, "condition", "Trigger"); + } + + /** + * Creates a new trigger based on the given condition. + * + *

Polled by the default scheduler button loop. + * + * @param condition the condition represented by this trigger + */ + public Trigger(BooleanSupplier condition) { + this(Scheduler.getInstance(), condition); + } + + // For internal use + private Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition) { + this.scheduler = scheduler; + m_loop = loop; + m_condition = condition; + } + + /** + * Starts the given command whenever the condition changes from `false` to `true`. + * + * @param command the command to start + * @return this trigger, so calls can be chained + */ + public Trigger onTrue(Command command) { + requireNonNullParam(command, "command", "onTrue"); + addBinding(BindingType.SCHEDULE_ON_RISING_EDGE, command); + return this; + } + + /** + * Starts the given command whenever the condition changes from `true` to `false`. + * + * @param command the command to start + * @return this trigger, so calls can be chained + */ + public Trigger onFalse(Command command) { + requireNonNullParam(command, "command", "onFalse"); + addBinding(BindingType.SCHEDULE_ON_FALLING_EDGE, command); + return this; + } + + /** + * Starts the given command when the condition changes to `true` and cancels it when the condition + * changes to `false`. + * + *

Doesn't re-start the command if it ends while the condition is still `true`. + * + * @param command the command to start + * @return this trigger, so calls can be chained + */ + public Trigger whileTrue(Command command) { + requireNonNullParam(command, "command", "whileTrue"); + addBinding(BindingType.RUN_WHILE_HIGH, command); + return this; + } + + /** + * Starts the given command when the condition changes to `false` and cancels it when the + * condition changes to `true`. + * + *

Doesn't re-start the command if it ends while the condition is still `false`. + * + * @param command the command to start + * @return this trigger, so calls can be chained + */ + public Trigger whileFalse(Command command) { + requireNonNullParam(command, "command", "whileFalse"); + addBinding(BindingType.RUN_WHILE_LOW, command); + return this; + } + + /** + * Toggles a command when the condition changes from `false` to `true`. + * + * @param command the command to toggle + * @return this trigger, so calls can be chained + */ + public Trigger toggleOnTrue(Command command) { + requireNonNullParam(command, "command", "toggleOnTrue"); + addBinding(BindingType.TOGGLE_ON_RISING_EDGE, command); + return this; + } + + /** + * Toggles a command when the condition changes from `true` to `false`. + * + * @param command the command to toggle + * @return this trigger, so calls can be chained + */ + public Trigger toggleOnFalse(Command command) { + requireNonNullParam(command, "command", "toggleOnFalse"); + addBinding(BindingType.TOGGLE_ON_FALLING_EDGE, command); + return this; + } + + @Override + public boolean getAsBoolean() { + return m_condition.getAsBoolean(); + } + + /** + * Composes two triggers with logical AND. + * + * @param trigger the condition to compose with + * @return A trigger which is active when both component triggers are active. + */ + public Trigger and(BooleanSupplier trigger) { + return new Trigger( + scheduler, m_loop, () -> m_condition.getAsBoolean() && trigger.getAsBoolean()); + } + + /** + * Composes two triggers with logical OR. + * + * @param trigger the condition to compose with + * @return A trigger which is active when either component trigger is active. + */ + public Trigger or(BooleanSupplier trigger) { + return new Trigger( + scheduler, m_loop, () -> m_condition.getAsBoolean() || trigger.getAsBoolean()); + } + + /** + * Creates a new trigger that is active when this trigger is inactive, i.e. that acts as the + * negation of this trigger. + * + * @return the negated trigger + */ + public Trigger negate() { + return new Trigger(scheduler, m_loop, () -> !m_condition.getAsBoolean()); + } + + /** + * Creates a new debounced trigger from this trigger - it will become active when this trigger has + * been active for longer than the specified period. + * + * @param duration The debounce period. + * @return The debounced trigger (rising edges debounced only) + */ + public Trigger debounce(Time duration) { + return debounce(duration, Debouncer.DebounceType.kRising); + } + + /** + * Creates a new debounced trigger from this trigger - it will become active when this trigger has + * been active for longer than the specified period. + * + * @param seconds The debounce period. + * @param type The debounce type. + * @return The debounced trigger. + */ + public Trigger debounce(Time duration, Debouncer.DebounceType type) { + return new Trigger( + scheduler, + m_loop, + new BooleanSupplier() { + final Debouncer m_debouncer = new Debouncer(duration.in(Seconds), type); + + @Override + public boolean getAsBoolean() { + return m_debouncer.calculate(m_condition.getAsBoolean()); + } + }); + } + + private void poll() { + var signal = signal(); + + if (signal == m_previousSignal) { + // No change in the signal. Nothing to do + return; + } + + if (signal == Signal.HIGH) { + // Signal is now high when it wasn't before - a rising edge + scheduleBindings(BindingType.SCHEDULE_ON_RISING_EDGE); + scheduleBindings(BindingType.RUN_WHILE_HIGH); + cancelBindings(BindingType.RUN_WHILE_LOW); + toggleBindings(BindingType.TOGGLE_ON_RISING_EDGE); + } + + if (signal == Signal.LOW) { + // Signal is now low when it wasn't before - a falling edge + scheduleBindings(BindingType.SCHEDULE_ON_FALLING_EDGE); + scheduleBindings(BindingType.RUN_WHILE_LOW); + cancelBindings(BindingType.RUN_WHILE_HIGH); + toggleBindings(BindingType.TOGGLE_ON_FALLING_EDGE); + } + + m_previousSignal = signal; + } + + private Signal signal() { + if (m_condition.getAsBoolean()) { + return Signal.HIGH; + } else { + return Signal.LOW; + } + } + + /** + * Schedules all commands bound to the given binding type. + * + * @param bindingType the binding type to schedule + */ + private void scheduleBindings(BindingType bindingType) { + m_bindings.getOrDefault(bindingType, List.of()).forEach(scheduler::schedule); + } + + /** + * Cancels all commands bound to the given binding type. + * + * @param bindingType the binding type to cancel + */ + private void cancelBindings(BindingType bindingType) { + m_bindings.getOrDefault(bindingType, List.of()).forEach(scheduler::cancel); + } + + /** + * Toggles all commands bound to the given binding type. If a command is currently scheduled or + * running, it will be canceled; otherwise, it will be scheduled. + * + * @param bindingType the binding type to cancel + */ + private void toggleBindings(BindingType bindingType) { + m_bindings + .getOrDefault(bindingType, List.of()) + .forEach( + command -> { + if (scheduler.isScheduledOrRunning(command)) { + scheduler.cancel(command); + } else { + scheduler.schedule(command); + } + }); + } + + private void addBinding(BindingType bindingType, Command command) { + m_bindings.computeIfAbsent(bindingType, _k -> new ArrayList<>()).add(command); + + // Ensure this trigger is bound to the event loop. NOP if already bound + m_loop.bind(m_eventLoopCallback); + } +} diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java new file mode 100644 index 00000000000..89dfef772da --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java @@ -0,0 +1,130 @@ +// 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.commandsv3.button; + +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.Coroutine; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import java.util.concurrent.atomic.AtomicBoolean; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class TriggerTest { + private Scheduler scheduler; + + @BeforeEach + void setup() { + scheduler = new Scheduler(); + } + + @Test + void onTrue() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.onTrue(command); + + signal.set(true); + scheduler.run(); + + assertTrue(scheduler.isRunning(command), "Command was not scheduled on rising edge"); + + signal.set(false); + scheduler.run(); + assertTrue(scheduler.isRunning(command), "Command should still be running on falling edge"); + } + + @Test + void onFalse() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.onFalse(command); + + scheduler.run(); + assertTrue(scheduler.isRunning(command), "Command should be scheduled when signal starts low"); + + signal.set(true); + scheduler.run(); + assertTrue(scheduler.isRunning(command), "Command should still be running rising falling edge"); + } + + @Test + void whileTrue() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.whileTrue(command); + + signal.set(true); + scheduler.run(); + + assertTrue(scheduler.isRunning(command), "Command was not scheduled on rising edge"); + + signal.set(false); + scheduler.run(); + assertFalse(scheduler.isRunning(command), "Command should be cancelled on falling edge"); + } + + @Test + void whileFalse() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.whileFalse(command); + + scheduler.run(); + assertTrue(scheduler.isRunning(command), "Command should be scheduled when signal starts low"); + + signal.set(true); + scheduler.run(); + assertFalse(scheduler.isRunning(command), "Command should be cancelled on rising edge"); + } + + @Test + void toggleOnTrue() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.toggleOnTrue(command); + + scheduler.run(); + assertFalse(scheduler.isRunning(command)); + + signal.set(true); + scheduler.run(); + assertTrue(scheduler.isRunning(command)); + + signal.set(false); + scheduler.run(); + assertTrue(scheduler.isRunning(command)); + + signal.set(true); + scheduler.run(); + assertFalse(scheduler.isRunning(command)); + } + + @Test + void toggleOnFalse() { + var signal = new AtomicBoolean(false); + var trigger = new Trigger(scheduler, signal::get); + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.toggleOnFalse(command); + + scheduler.run(); + assertTrue(scheduler.isRunning(command)); + + signal.set(true); + scheduler.run(); + assertTrue(scheduler.isRunning(command)); + + signal.set(false); + scheduler.run(); + assertFalse(scheduler.isRunning(command)); + } +} From 10869c8cc81e818cae6f1895a16e50112d6dcfb9 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:16:38 -0400 Subject: [PATCH 005/153] Add example program for commandsv3 Mirrors the existing example for commandsv2 --- wpilibjExamples/build.gradle | 1 + .../examples/coroutines/AsyncCommandBot.java | 102 +++++++++++++++++ .../examples/coroutines/Constants.java | 90 +++++++++++++++ .../wpilibj/examples/coroutines/Main.java | 25 +++++ .../wpilibj/examples/coroutines/Robot.java | 86 +++++++++++++++ .../examples/coroutines/subsystems/Drive.java | 103 ++++++++++++++++++ .../coroutines/subsystems/Intake.java | 46 ++++++++ .../coroutines/subsystems/Pneumatics.java | 71 ++++++++++++ .../coroutines/subsystems/Shooter.java | 66 +++++++++++ .../coroutines/subsystems/Storage.java | 47 ++++++++ 10 files changed, 637 insertions(+) create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java diff --git a/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle index 0e8caf4f48b..67a2f37c611 100644 --- a/wpilibjExamples/build.gradle +++ b/wpilibjExamples/build.gradle @@ -22,6 +22,7 @@ dependencies { implementation project(':cscore') implementation project(':cameraserver') implementation project(':wpilibNewCommands') + implementation project(':commandsv3') implementation project(':romiVendordep') implementation project(':xrpVendordep') implementation project(':epilogue-runtime') diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java new file mode 100644 index 00000000000..b7c44efc1e4 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java @@ -0,0 +1,102 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.examples.coroutines; + +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.button.CommandXboxController; +import edu.wpi.first.wpilibj.commandsv3.button.Trigger; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.AutoConstants; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.OIConstants; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; +import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Drive; +import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Intake; +import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Pneumatics; +import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Shooter; +import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Storage; + +/** + * This class is where the bulk of the robot should be declared. Since Command-based is a + * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} + * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including + * subsystems, commands, and button mappings) should be declared here. + */ +public class AsyncCommandBot { + // The robot's subsystems + private final Drive m_drive = new Drive(); + private final Intake m_intake = new Intake(); + private final Storage m_storage = new Storage(); + private final Shooter m_shooter = new Shooter(); + private final Pneumatics m_pneumatics = new Pneumatics(); + + // The driver's controller + private final CommandXboxController m_driverController = + new CommandXboxController(OIConstants.kDriverControllerPort); + + /** + * Use this method to define bindings between conditions and commands. These are useful for + * automating robot behaviors based on button and sensor input. + * + *

Should be called during {@link Robot#robotInit()}. + * + *

Event binding methods are available on the {@link Trigger} class. + */ + public void configureBindings() { + // Automatically run the storage motor whenever the ball storage is not full, + // and turn it off whenever it fills. Uses subsystem-hosted trigger to + // improve readability and make inter-subsystem communication easier. + m_storage.hasCargo.whileFalse(m_storage.runCommand()); + + // Automatically disable and retract the intake whenever the ball storage is full. + m_storage.hasCargo.onTrue(m_intake.retractCommand()); + + // Control the drive with split-stick arcade controls + m_drive.setDefaultCommand( + m_drive.arcadeDriveCommand( + () -> -m_driverController.getLeftY(), () -> -m_driverController.getRightX())); + + // Deploy the intake with the X button + m_driverController.x().onTrue(m_intake.intakeCommand()); + // Retract the intake with the Y button + m_driverController.y().onTrue(m_intake.retractCommand()); + + // Fire the shooter with the A button + m_driverController.a().onTrue(loadAndShoot()); + + // Toggle compressor with the Start button + m_driverController.start() + .onTrue(m_pneumatics.disableCompressor()) + .onFalse(m_pneumatics.enableCompressor()); + } + + private Command loadAndShoot() { + return Command + .requiring(m_shooter, m_storage) + .executing((coroutine) -> { + while (coroutine.yield()) { + m_storage.run(); + m_shooter.ramp(ShooterConstants.kShooterTarget); + + if (m_shooter.atSetpoint()) { + m_shooter.feed(); + } else { + m_shooter.stop(); + } + } + }) + .named("Shoot"); + } + + /** + * Use this to define the command that runs during autonomous. + * + *

Scheduled during {@link Robot#autonomousInit()}. + */ + public Command getAutonomousCommand() { + // Drive forward for 2 meters at half speed with a 3 second timeout + return m_drive + .driveDistanceCommand(AutoConstants.kDriveDistance, AutoConstants.kDriveSpeed) + .withTimeout(AutoConstants.kTimeout); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java new file mode 100644 index 00000000000..21b9d680a8b --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java @@ -0,0 +1,90 @@ +// 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.examples.coroutines; + +import static edu.wpi.first.units.Units.Meters; +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.Seconds; + +import edu.wpi.first.math.util.Units; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Distance; +import edu.wpi.first.units.measure.Time; + +/** + * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean + * constants. This class should not be used for any other purpose. All constants should be declared + * globally (i.e. public static). Do not put anything functional in this class. + * + *

It is advised to statically import this class (or one of its inner classes) wherever the + * constants are needed, to reduce verbosity. + */ +public final class Constants { + public static final class DriveConstants { + public static final int kLeftMotor1Port = 0; + public static final int kLeftMotor2Port = 1; + public static final int kRightMotor1Port = 2; + public static final int kRightMotor2Port = 3; + + public static final int[] kLeftEncoderPorts = {0, 1}; + public static final int[] kRightEncoderPorts = {2, 3}; + public static final boolean kLeftEncoderReversed = false; + public static final boolean kRightEncoderReversed = true; + + public static final int kEncoderCPR = 1024; + public static final double kWheelDiameterMeters = Units.inchesToMeters(6); + public static final double kEncoderDistancePerPulse = + // Assumes the encoders are directly mounted on the wheel shafts + (kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR; + } + + public static final class ShooterConstants { + public static final int[] kEncoderPorts = {4, 5}; + public static final boolean kEncoderReversed = false; + public static final int kEncoderCPR = 1024; + public static final double kEncoderDistancePerPulse = + // Distance units will be rotations + 1.0 / (double) kEncoderCPR; + + public static final int kShooterMotorPort = 4; + public static final int kFeederMotorPort = 5; + + public static final double kShooterFreeRPS = 5300; + public static final AngularVelocity kShooterTarget = RotationsPerSecond.of(4000); + public static final double kShooterToleranceRPS = 50; + + // These are not real PID gains, and will have to be tuned for your specific robot. + public static final double kP = 1; + + // On a real robot the feedforward constants should be empirically determined; these are + // reasonable guesses. + public static final double kSVolts = 0.05; + public static final double kVVoltSecondsPerRotation = + // Should have value 12V at free speed... + 12.0 / kShooterFreeRPS; + + public static final double kFeederSpeed = 0.5; + } + + public static final class IntakeConstants { + public static final int kMotorPort = 6; + public static final int[] kSolenoidPorts = {2, 3}; + } + + public static final class StorageConstants { + public static final int kMotorPort = 7; + public static final int kBallSensorPort = 6; + } + + public static final class AutoConstants { + public static final Time kTimeout = Seconds.of(3); + public static final Distance kDriveDistance = Meters.of(2); + public static final double kDriveSpeed = 0.5; + } + + public static final class OIConstants { + public static final int kDriverControllerPort = 0; + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java new file mode 100644 index 00000000000..f0fe058ddd4 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.examples.coroutines; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java new file mode 100644 index 00000000000..9248f1848a9 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java @@ -0,0 +1,86 @@ +// 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.examples.coroutines; + +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.Scheduler; + +/** + * The VM is configured to automatically run this class, and to call the functions corresponding to + * each mode, as described in the TimedRobot documentation. If you change the name of this class or + * the package after creating this project, you must also update the build.gradle file in the + * project. + */ +public class Robot extends TimedRobot { + private Command m_autonomousCommand; + + private final AsyncCommandBot m_robot = new AsyncCommandBot(); + + /** + * This function is run when the robot is first started up and should be used for any + * initialization code. + */ + @Override + public void robotInit() { + // Configure default commands and condition bindings on robot startup + m_robot.configureBindings(); + } + + /** + * This function is called every robot packet, no matter the mode. Use this for items like + * diagnostics that you want ran during disabled, autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic functions, but before LiveWindow and + * SmartDashboard integrated updating. + */ + @Override + public void robotPeriodic() { + Scheduler.getInstance().run(); + } + + /** This function is called once each time the robot enters Disabled mode. */ + @Override + public void disabledInit() {} + + @Override + public void disabledPeriodic() {} + + @Override + public void autonomousInit() { + m_autonomousCommand = m_robot.getAutonomousCommand(); + + if (m_autonomousCommand != null) { + Scheduler.getInstance().schedule(m_autonomousCommand); + } + } + + /** This function is called periodically during autonomous. */ + @Override + public void autonomousPeriodic() {} + + @Override + public void teleopInit() { + // This makes sure that the autonomous stops running when + // teleop starts running. If you want the autonomous to + // continue until interrupted by another command, remove + // this line or comment it out. + Scheduler.getInstance().cancel(m_autonomousCommand); + } + + /** This function is called periodically during operator control. */ + @Override + public void teleopPeriodic() {} + + @Override + public void testInit() { + // Cancels all running commands at the start of test mode. + Scheduler.getInstance().cancelAll(); + } + + /** This function is called periodically during test mode. */ + @Override + public void testPeriodic() {} +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java new file mode 100644 index 00000000000..23082e84532 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java @@ -0,0 +1,103 @@ +// 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.examples.coroutines.subsystems; + +import static edu.wpi.first.units.Units.Meters; + +import edu.wpi.first.units.measure.Distance; +import edu.wpi.first.util.sendable.SendableRegistry; +import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import edu.wpi.first.wpilibj.drive.DifferentialDrive; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.DriveConstants; +import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; +import java.util.function.DoubleSupplier; + +public class Drive extends RequireableResource { + // The motors on the left side of the drive. + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); + + // The motors on the right side of the drive. + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); + + // The robot's drive + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); + + // The left-side drive encoder + private final Encoder m_leftEncoder = + new Encoder( + DriveConstants.kLeftEncoderPorts[0], + DriveConstants.kLeftEncoderPorts[1], + DriveConstants.kLeftEncoderReversed); + + // The right-side drive encoder + private final Encoder m_rightEncoder = + new Encoder( + DriveConstants.kRightEncoderPorts[0], + DriveConstants.kRightEncoderPorts[1], + DriveConstants.kRightEncoderReversed); + + /** Creates a new Drive subsystem. */ + public Drive() { + super("Drive"); + + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + + // We need to invert one side of the drivetrain so that positive voltages + // result in both sides moving forward. Depending on how your robot's + // gearbox is constructed, you might have to invert the left side instead. + m_rightLeader.setInverted(true); + + // Sets the distance per pulse for the encoders + m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); + m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); + } + + /** + * Returns a command that drives the robot with arcade controls. + * + * @param fwd the commanded forward movement + * @param rot the commanded rotation + */ + public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) { + // A split-stick arcade command, with forward/backward controlled by the left + // hand, and turning controlled by the right. + return run((coroutine) -> { + while (coroutine.yield()) { + m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble()); + } + }).named("arcadeDrive"); + } + + /** + * Returns a command that drives the robot forward a specified distance at a specified speed. + * + * @param distance The distance to drive forward in meters + * @param speed The fraction of max speed at which to drive + */ + public Command driveDistanceCommand(Distance distance, double speed) { + double distanceMeters = distance.in(Meters); + + return run((coroutine) -> { + m_leftEncoder.reset(); + m_rightEncoder.reset(); + + while (Math.max(m_leftEncoder.getDistance(), m_rightEncoder.getDistance()) < distanceMeters) { + coroutine.yield(); + m_drive.arcadeDrive(speed, 0); + } + + m_drive.stopMotor(); + }).named("DriveDistance[" + distance.toLongString() + ", @" + speed + "]"); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java new file mode 100644 index 00000000000..a8d74fa2758 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java @@ -0,0 +1,46 @@ +// 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.examples.coroutines.subsystems; + +import static edu.wpi.first.wpilibj.examples.coroutines.Constants.IntakeConstants; + +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; + +public class Intake extends RequireableResource { + private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort); + + // Double solenoid connected to two channels of a PCM with the default CAN ID + private final DoubleSolenoid m_pistons = + new DoubleSolenoid( + PneumaticsModuleType.CTREPCM, + IntakeConstants.kSolenoidPorts[0], + IntakeConstants.kSolenoidPorts[1]); + + public Intake() { + super("Intake"); + } + + /** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */ + public Command intakeCommand() { + return run((coroutine) -> { + m_pistons.set(DoubleSolenoid.Value.kForward); + while (coroutine.yield()) { + m_motor.set(1); + } + }).named("Intake"); + } + + /** Returns a command that turns off and retracts the intake. */ + public Command retractCommand() { + return run((coroutine) -> { + m_motor.disable(); + m_pistons.set(DoubleSolenoid.Value.kReverse); + }).named("Retract"); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java new file mode 100644 index 00000000000..9798519a431 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java @@ -0,0 +1,71 @@ +// 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.examples.coroutines.subsystems; + +import edu.wpi.first.wpilibj.AnalogPotentiometer; +import edu.wpi.first.wpilibj.Compressor; +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; + +/** Subsystem for managing the compressor, pressure sensor, etc. */ +public class Pneumatics extends RequireableResource { + // External analog pressure sensor + // product-specific voltage->pressure conversion, see product manual + // in this case, 250(V/5)-25 + // the scale parameter in the AnalogPotentiometer constructor is scaled from 1 instead of 5, + // so if r is the raw AnalogPotentiometer output, the pressure is 250r-25 + static final double kScale = 250; + static final double kOffset = -25; + private final AnalogPotentiometer m_pressureTransducer = + new AnalogPotentiometer(/* the AnalogIn port*/ 2, kScale, kOffset); + + // Compressor connected to a PCM with a default CAN ID (0) + // Note: the compressor is enabled by default + private final Compressor m_compressor = new Compressor(PneumaticsModuleType.CTREPCM); + + public Pneumatics() { + super("Pneumatics"); + var tab = Shuffleboard.getTab("Pneumatics"); + tab.addDouble("External Pressure [PSI]", this::getPressure); + } + + /** + * Query the analog pressure sensor. + * + * @return the measured pressure, in PSI + */ + private double getPressure() { + // Get the pressure (in PSI) from an analog pressure sensor connected to the RIO. + return m_pressureTransducer.get(); + } + + /** + * Disable the compressor closed-loop control. The compressor can be re-enabled with + * {@link #enableCompressor()}. + * + * @return command + */ + public Command disableCompressor() { + return run((coroutine) -> { + m_compressor.disable(); + coroutine.park(); + }).named("Disable Compressor"); + } + + /** + * Enable the compressor closed-loop control. The compressor can be disabled again with + * {@link #disableCompressor()}. + * + * @return command + */ + public Command enableCompressor() { + return run((coroutine) -> { + m_compressor.enableDigital(); + coroutine.park(); + }).named("Enable Compressor"); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java new file mode 100644 index 00000000000..14ede9d40aa --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java @@ -0,0 +1,66 @@ +// 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.examples.coroutines.subsystems; + +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.Volts; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; +import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; + +public class Shooter extends RequireableResource { + private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort); + private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort); + private final Encoder m_shooterEncoder = + new Encoder( + ShooterConstants.kEncoderPorts[0], + ShooterConstants.kEncoderPorts[1], + ShooterConstants.kEncoderReversed); + private final SimpleMotorFeedforward m_shooterFeedforward = + new SimpleMotorFeedforward( + ShooterConstants.kSVolts, ShooterConstants.kVVoltSecondsPerRotation); + private final PIDController m_shooterFeedback = new PIDController(ShooterConstants.kP, 0.0, 0.0); + + /** The shooter subsystem for the robot. */ + public Shooter() { + super("Shooter"); + m_shooterFeedback.setTolerance(ShooterConstants.kShooterToleranceRPS); + m_shooterEncoder.setDistancePerPulse(ShooterConstants.kEncoderDistancePerPulse); + + // Set default command to turn off both the shooter and feeder motors, and then idle + setDefaultCommand( + run( + (coroutine) -> { + m_shooterMotor.disable(); + m_feederMotor.disable(); + coroutine.park(); + }) + .named("Idle")); + } + + public void ramp(AngularVelocity setpoint) { + m_shooterMotor.set( + m_shooterFeedforward.calculate(setpoint).in(Volts) + + m_shooterFeedback.calculate( + m_shooterEncoder.getRate(), setpoint.in(RotationsPerSecond))); + } + + public boolean atSetpoint() { + return m_shooterFeedback.atSetpoint(); + } + + public void feed() { + m_feederMotor.set(1); + } + + public void stop() { + m_feederMotor.set(0); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java new file mode 100644 index 00000000000..70f8a168b1f --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java @@ -0,0 +1,47 @@ +// 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.examples.coroutines.subsystems; + +import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj.commandsv3.Command; +import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import edu.wpi.first.wpilibj.commandsv3.button.Trigger; +import edu.wpi.first.wpilibj.examples.coroutines.Constants.StorageConstants; +import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; + +public class Storage extends RequireableResource { + private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort); + private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort); + + // Expose trigger from subsystem to improve readability and ease + // inter-subsystem communications + /** Whether the ball storage is full. */ + @SuppressWarnings("checkstyle:MemberName") + public final Trigger hasCargo = new Trigger(m_ballSensor::get); + + /** Create a new Storage subsystem. */ + public Storage() { + super("Storage"); + + // Set default command to turn off the storage motor and then idle + setDefaultCommand(run((coroutine) -> { + m_motor.disable(); + coroutine.park(); + }).named("Idle")); + } + + public void run() { + m_motor.set(1); + } + + /** Returns a command that runs the storage motor indefinitely. */ + public Command runCommand() { + return run((coroutine) -> { + while (coroutine.yield()) { + run(); + } + }).named("Run"); + } +} From 9173146f94a29b4d92233a7bc330c3db7aa7b85e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 19 Apr 2025 15:30:05 -0400 Subject: [PATCH 006/153] Add comment on exception handling --- wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 61c96bd6a69..0b8e4fb86a4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -296,6 +296,13 @@ private static void runRobot(Supplier robotSupplier) { try { robot.startCompetition(); } catch (Throwable throwable) { + // TODO: This can do some weird things with the command framework. + // An exception thrown during a command's execution will be wrapped and rethrown as a + // CommandExecutionException, with the cause being that original exception (which may + // in turn also have a cause, etc). + // This bit of code means that an exception thrown by a method called within a command + // will be reported differently than that same exception when called outside a command + // TODO: Should we just report every error up the stack, instead of only the first level? Throwable cause = throwable.getCause(); if (cause != null) { throwable = cause; From ded13945a2c0b048394e9b367a737be19ede6735 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 22 Apr 2025 20:38:28 -0400 Subject: [PATCH 007/153] Add Coroutine.fork --- .../first/wpilibj/commandsv3/Coroutine.java | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java index c90cdaea416..2d21021e73a 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java @@ -48,6 +48,30 @@ public void park() { } } + /** + * Forks off a command. It will run until its natural completion, the parent command exits, + * or the parent command cancels it. The parent command will continue executing while the + * forked command runs, and can resync with the forked command using {@link #await(Command)}. + *

+ * {@snippet lang = java: + * Command example() { + * return Command.noRequirements((coroutine) -> { + * Command inner = ...; + * coroutine.fork(inner); + * // ... do more things + * // then sync back up with the inner command + * coroutine.await(inner); + * }).named("Example"); + * } + * } + * + * @param command The command to fork. + */ + public void fork(Command command) { + // Shorthand; this is handy for user-defined compositions + scheduler.schedule(command); + } + /** * Awaits completion of a command. If the command is not currently scheduled or running, it will * be scheduled automatically. From 17bb1a615a8028ad4a94ed60636748ec5c3207ff Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 22 Apr 2025 20:39:33 -0400 Subject: [PATCH 008/153] Add tests for sibling requirements and nested oneshots --- .../wpilibj/commandsv3/SchedulerTest.java | 51 +++++++++++++++++++ 1 file changed, 51 insertions(+) diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java index c95691983db..a42d20b3d7c 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java @@ -17,6 +17,7 @@ import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; +import java.util.function.Supplier; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.junit.jupiter.api.Timeout; @@ -644,6 +645,56 @@ void protobuf() { messageJson); } + @Test + void siblingsInCompositionCannotShareRequirements() { + var resource = new RequireableResource("The Resource", scheduler); + var group = Command.noRequirements(co -> { + co.fork(resource.run(Coroutine::park).named("First")); + co.fork(resource.run(Coroutine::park).named("Second")); + }).named("Group"); + + scheduler.schedule(group); + + try { + scheduler.run(); + fail("An error should have been thrown"); + } catch (CommandExecutionException e) { + assertEquals(group, e.getCommand()); + if (e.getCause() instanceof IllegalArgumentException argumentException) { + assertEquals( + "Command Second requires resources that are already used by First. " + + "Both require The Resource", + argumentException.getMessage()); + } else { + fail("Unexpected cause: " + e.getCause()); + } + } + } + + @Test + void nestedOneShotCompositionsAllRunInOneCycle() { + var runs = new AtomicInteger(0); + Supplier makeOneShot = () -> Command.noRequirements(_c -> runs.incrementAndGet()).named("One Shot"); + var command = Command.noRequirements(co -> { + co.fork(makeOneShot.get()); + co.fork(makeOneShot.get()); + co.fork(Command.noRequirements(inner -> inner.fork(makeOneShot.get())).named("Inner")); + co.fork( + Command.noRequirements(co2 -> { + co2.fork(makeOneShot.get()); + co2.fork( + Command.noRequirements(co3 -> { + co3.fork(makeOneShot.get()); + }).named("3")); + }).named("2")); + }).named("Command"); + + scheduler.schedule(command); + scheduler.run(); + assertEquals(5, runs.get(), "All oneshot commands should have run"); + assertFalse(scheduler.isRunning(command), "Command should have exited after one cycle"); + } + record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { @Override public void run(Coroutine coroutine) { From dd0420e2e80a2509d091860a8faca76339a8fa9f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 22 Apr 2025 20:39:59 -0400 Subject: [PATCH 009/153] Make documentation comment a little clearer --- .../main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java index d8f515a1084..f78600aaebd 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java @@ -289,8 +289,8 @@ private void evictConflictingOnDeckCommands(Command command) { } /** - * Cancels all running commands with which an incoming state conflicts. Ancestor commands will not - * be canceled. + * Cancels all running commands with which an incoming state conflicts. Ancestor commands of the + * incoming state will not be canceled. */ private void evictConflictingRunningCommands(CommandState incomingState) { // The set of root states with which the incoming state conflicts but does not inherit from From dce090361d3fad8da2409777d69d22f685efcbbf Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 23 Apr 2025 07:01:30 -0400 Subject: [PATCH 010/153] Change Coroutine.fork to accept multiple commands --- .../first/wpilibj/commandsv3/Coroutine.java | 8 ++-- .../wpilibj/commandsv3/CoroutineTest.java | 40 +++++++++++++++++++ .../first/wpilibj/commandsv3/NullCommand.java | 24 +++++++++++ 3 files changed, 69 insertions(+), 3 deletions(-) create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java create mode 100644 commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java index 2d21021e73a..36d78e364f3 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java @@ -65,11 +65,13 @@ public void park() { * } * } * - * @param command The command to fork. + * @param commands The commands to fork. */ - public void fork(Command command) { + public void fork(Command... commands) { // Shorthand; this is handy for user-defined compositions - scheduler.schedule(command); + for (var command : commands) { + scheduler.schedule(command); + } } /** diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java new file mode 100644 index 00000000000..ae910b4db95 --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java @@ -0,0 +1,40 @@ +// 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.commandsv3; + +import static org.junit.jupiter.api.Assertions.assertTrue; + +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class CoroutineTest { + Scheduler scheduler; + ContinuationScope scope; + + @BeforeEach + void setup() { + scheduler = new Scheduler(); + scope = new ContinuationScope("Test Scope"); + } + + + @Test + void forkMany() { + var a = new NullCommand(); + var b = new NullCommand(); + var c = new NullCommand(); + + var all = Command.noRequirements(co -> { + co.fork(a, b, c); + co.park(); + }).named("Fork Many"); + + scheduler.schedule(all); + scheduler.run(); + assertTrue(scheduler.isRunning(a)); + assertTrue(scheduler.isRunning(b)); + assertTrue(scheduler.isRunning(c)); + } +} diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java new file mode 100644 index 00000000000..93176695c2b --- /dev/null +++ b/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java @@ -0,0 +1,24 @@ +// 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.commandsv3; + +import java.util.Set; + +class NullCommand implements Command { + @Override + public void run(Coroutine coroutine) { + coroutine.park(); + } + + @Override + public String name() { + return "Null Command"; + } + + @Override + public Set requirements() { + return Set.of(); + } +} From b669696a70b62aa051b0d29cdade2349e8e8ffeb Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 23 Apr 2025 07:02:03 -0400 Subject: [PATCH 011/153] Add copyright headers to generated protobuf classes --- .../wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java | 4 ++++ .../wpilibj/commandsv3/proto/ProtobufRequireableResource.java | 4 ++++ .../wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java | 4 ++++ .../edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java | 4 ++++ 4 files changed, 16 insertions(+) diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java index 7a1206e0435..8af72b66909 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java @@ -1,3 +1,7 @@ +// 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. + // Code generated by protocol buffer compiler. Do not edit! package edu.wpi.first.wpilibj.commandsv3.proto; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java index c3ba80225a1..cc95122d693 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java @@ -1,3 +1,7 @@ +// 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. + // Code generated by protocol buffer compiler. Do not edit! package edu.wpi.first.wpilibj.commandsv3.proto; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java index bee98f6bda4..4f93f284ca0 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java @@ -1,3 +1,7 @@ +// 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. + // Code generated by protocol buffer compiler. Do not edit! package edu.wpi.first.wpilibj.commandsv3.proto; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java index 9418ce027f1..b4eb075335b 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java +++ b/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java @@ -1,3 +1,7 @@ +// 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. + // Code generated by protocol buffer compiler. Do not edit! package edu.wpi.first.wpilibj.commandsv3.proto; From 676e787f1910e871847099bde4e344f90cc27e38 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 23 Apr 2025 20:23:34 -0400 Subject: [PATCH 012/153] Add first draft of a commands v3 design doc --- design-docs/commands-v3.md | 305 +++++++++++++++++++++++++++++++++++++ 1 file changed, 305 insertions(+) create mode 100644 design-docs/commands-v3.md diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md new file mode 100644 index 00000000000..e11106e2f58 --- /dev/null +++ b/design-docs/commands-v3.md @@ -0,0 +1,305 @@ +# WPILib Commands Version 3 + +[TOC] + +## Problem Statement {#problem-statement} + +The WPILib command framework uses cooperative multitasking to execute many commands concurrently; +each command has its own `execute()` function called periodically by the scheduler’s `run()` loop. +This API share has a steep learning curve, since new students learn looping by writing their own +`for` or `while` loops - not by using a framework that does the looping for them. Programmers +unfamiliar with the command framework commonly run into a problem where they write a while loop +inside their command’s `execute()` function, thus stalling the scheduler (and, by extension, the +entire robot program) by never ceding control until its end condition is met. + +Version 3 of the commands framework proposes to fix this issue by leveraging a new API introduced in +Java 21: continuations. While they are currently an internal JDK API used to underpin virtual thread +runtimes, we can still access and use it. Continuations are used by the JDK to take and save a +snapshot of a mounted function’s call stack and registers, and can be remounted later to continue +from where it left off; a canceled command would simply never be remounted, and its continuation +left for the garbage collector to clean up. + +## Goals + +### Make command logic look like normal functions + +The hardest part of learning the v1 and v2 command frameworks is the splitting out of logic into +separate init/execute/end/isFinished methods. Coroutines allow us to merge those all back into a +single function: + +```java +void commandBody(Coroutine coroutine) { + initialize(); + while (!isFinished()) { + execute(); + coroutine.yield(); + } + end(); +} +``` + +Coroutines allow commands to be normal methods that yield control back to the scheduler mid-method; +the scheduler will issue a continuation to each command, and the JVM can unmount a continuation - +saving the stack and registers - which can be remounted later. **The primary goal of the new +framework is to allow for commands to be written as normal methods by taking advantage of this +mount/unmount feature.** Everything else is focused on quality of life improvements to the +framework. + +### Forced Naming + +The v2 commands framework makes naming opt-in; it is very easy to forget to set a name on a command +in a factory method, making telemetry less useful than it should be; seeing a +“SequentialCommandGroup” in logs isn’t very useful. The v3 framework will make command names +required in order for commands to be constructed. See [Telemetry](#telemetry) for details. + +### Uncommanded Behavior + +Command groups - or, more generally, commands that schedule other commands - need to own all +resources needed by all their inner commands. However, if they don’t *directly* control a resource, +then they will still own the resource whenever they’re not running an inner command that uses it, +causing the resource to be in an *uncommanded state*. This can cause unexpected behavior with +parallel groups where inner commands don’t all end at the same time, and especially with sequential +groups. For example, something as seemingly basic as `elevator.toL4().andThen(coral.score())` would +*own* the elevator and coral resources for the entire sequence, but not control the elevator during +the coral scoring section, nor control the coral scoring mechanism while the elevator is moving. + +The v2 framework worked around this problem with so-called proxy commands, which have no +requirements of their own and simply schedule and await the *real* command. This removed the +requirement for their used subsystems from the parent group, and allowed for the subsystem’s default +command to run after the proxied command completed. It also meant that *every* command that required +that subsystem would also need to be proxied; otherwise, the group would still have ownership of the +subsystem, and the proxied command would interrupt it (and thus itself). + +The v3 framework allows nested commands to use resources not required by the parent command; +however, the built-in parallel and sequential groups will take full ownership of all resources +required by their nested commands for safety and to keep behavior parity with previous command +frameworks. + +```java +public Command outerCommand() { + // The outer command only requires the outer resource + return run(coroutine -> { + // But can schedule a command that requires any other resource + coroutine.await(innerResource.innerCommand()); + // And only requires that inner resource while its command runs + coroutine.await(otherResource().otherCommand()); + }).named("Outer"); +} +``` + +Scheduling a command that requires an inner resource will also cancel its parent, even if the parent +does not require that inner resource. Using the above example, directly scheduling a command that +requires `innerResource` will cancel a running `outerCommand` - but only if `outerCommand` is +*currently using* the inner resource at the time. + +### Priority Levels + +Priority levels allow for finer-grained control over when commands should be interruptible than a +binary interrupt/ignore interrupt flag. This can be particularly helpful for LED control, where +teams use lights to indicate robot activity or error states with error indicators taking priority. + +### Suspend/Resume + +Allow commands to be temporarily paused while a higher priority or interrupting command runs, then +be automatically resumed after that higher priority command finishes. Note that resuming commands +must check for a condition to determine if they should still be running, since the time between +pause and resume can be arbitrarily long. + +Suspending a command will suspend all its children, regardless of if those children have declared +themselves suspendable or not. Likewise, cancelling a non-suspendable command will also cancel all +its children, even if some of those children are suspendable. + +Suspending a command that already has suspended children will still suspend everything; however, +upon resume, those suspended children will remain suspended. + +### Improved Transparency + +The v2 commands framework only runs top-level commands in the scheduler; commands nested within a +composition like a sequential group or a simple `withTimeout` decoration are hidden from the +scheduler and do not appear in its sendable implementation, making telemetry difficult. A +“SequentialCommandGroup” in logs is less useful than “Wait 10 seconds -> Drive Forward”. Command +groups will automatically include the names of all their constituent commands, with options to +override when desired. + +The v3 framework will also provide a map of what command each resource is owned by. The v2 framework +only provides a list of the names of the running commands, without mapping those to subsystems. This +also makes telemetry difficult, since the order of commands in the list does not correspond with +subsystems; a command at a particular index may require different subsystems than a different +command at that same index that’s running at a later point in time, making data analysis in +AdvantageScope difficult since we can’t rely on consistent ordering. + +## Non-Goals + +### Preemptive Multitasking + +It is not a goal of the v3 framework to offer preemptive multitasking (that is, having the scheduler +forcibly suspend a long-running command in order to run another queued one). This would require +support from the JDK for allowing custom virtual thread schedulers, which it does not currently +offer, and a custom thread scheduler would be complicated and difficult to maintain. + +### Multithreading Support + +Like the previous iterations of the command-based framework, v3 will be designed for a +single-threaded environment. All commands will be run by a single thread, which is expected to be +the same thread on which commands are scheduled and canceled via triggers. No guarantees are made +for stability or proper functioning if used in a multithreaded environment. + + +## Implementation Details + +### Nomenclature + +**Schedule**: Adding a command to a queue in the scheduler, requesting that that command start +running in the next call to the scheduler’s `run()` method. + +**Mount**: Make a command active by resuming its stack and executing it on the scheduler’s thread. + +**Unmount**: Freeze a command’s stack and state and remove it from the scheduler’s thread. An +unmounted command may be re-mounted in the future. + +**Run**: Adding a command to the scheduler and have it begin executing. Every unfinished command +will be run by the scheduler until they reach a `Coroutine.yield()` call, at which point the command +is unmounted and the next command can begin. + +**Cancel**: Request that a command stop running. A command that is scheduled and hasn’t yet started +running will be removed from the queue of scheduled commands. Cancellation requests are handled at +the end of each `run() `invocation. Cancelled commands are unmounted and will not be re-mounted; +they must be rescheduled and be issued new carrier coroutines. + +**Interrupt**: Scheduling a command that requires one or more resources already in use by a running +command will interrupt and cancel that running command, so long as the running command has an equal +or lower priority level. Higher-priority commands cannot be interrupted by lower-priority ones. + +### Coroutines and Continuations + +`Continuation` and `ContinuationScope` are JDK-internal classes that manage stack saving and +loading (“unmounting” and “mounting”, respectively). Mounting a continuation essentially means +placing the continuation’s saved stack on top of the current stack. Calling +`Continuation.yield(ContinuationScope)` pauses the code that the continuation is evaluating and +cedes control back to the caller, which can then unmount the continuation. The scheduler uses this +by looping over every running command, mounting the continuation for the command, running the +command - which eventually either returns or calls `coroutine.yield()` - then unmounts the +continuation and moves on to the next command in the list. + +Coroutines are essentially wrappers around a continuation primitive that allows additional access to +the scheduler and provides async/await-like functionality. For example, `Coroutine.await(Command)` +will schedule a given command and call `yield()` in a loop until that command has completed +execution (note: this does *not* naively call `command.run(coroutine)`, which would hide the inner +command from the scheduler and potentially sidestep requirement mutexing) + +### Command Function Bodies + +Command logic lives in a single function `run` that accepts a `Coroutine` object argument. All +yielding is done via that coroutine, as is any management of nested commands (scheduling, awaiting, +cancelling, etc). + +The coroutine’s `yield()` method always returns `true`. When a command is cancelled, it is removed +from the set of running commands and its carrier objects left to be garbage collected. An +`onCancel()` method on the cancelled command will be invoked to let the command do any necessary +cleanup; this is needed because the command body will not be re-mounted and run, so a separate +function is used. Command builders allow this to be specified with a `whenCancelled(Runnable)` step. + +### Command Lifetimes + +All commands are managed and executed by the scheduler. No commands should manually run their inner +commands (which is what the old sequential and parallel groups did), since that hides those inner +commands from the scheduler and telemetry. However, this is not prohibited, nor would there be a way +to detect it. + +Inner commands are bound to the lifetime of their parents. Cancelling a higher-level command must +also cancel all the commands it scheduled (and so on down the hierarchy). Suspending a higher-level +command must likewise also suspend all inner commands, and resuming the higher-level command must +resume all suspended inner commands. Inner commands cannot be resumed before their parent command, +but may be suspended while the parent command still runs. + +When a command is running, the scheduler tracks in a wrapper CommandState object that includes the +command, the command that scheduled it (if applicable), and the coroutine object carrying the +command. + +Each command run has its own coroutine to back its execution. When a command finishes, its backing +continuation is done, and the command is removed from the scheduler. Any unfinished inner commands +are cancelled at this point. + +### Factory Methods and Builders + +In contrast with v2’s decorator API that returns a new command object for each modification (which +had some issues with naming and making telemetry difficult with deeply nested wrapper objects), v3 +uses builder objects that allow configuration to be set before creating a single command at the end. + +#### Forced Naming + +Builder objects will only permit command creation when a name for the command has been provided. + +#### Automatic Naming + +Parallel and sequential groups and builders permit automatically generated names to be used instead +of manually specified ones. + +Automatic sequence names will simply be the list of all the commands in the sequence, separated by +a “->” arrow sign; for example, “Step 1 -> Step 2 -> Step 3” + +Automatic parallel group names will be the list of the names of the commands in the group, separated +by a pipe “|”. Required commands will be in their own group, separated from non-required commands. +If either subgroup is empty, then there will be no indication in the output (ie, no empty group +token like “()” will appear) + +### Cooperative Multitasking + +All commands *must* yield control back to the coroutine in their control loops. Because we cannot +preempt a running command at any arbitrary point, the command must explicitly and deliberately cede +control back to the scheduler in order for the framework to function. Commands may do this by +calling `coroutine.yield()` on the injected coroutine object, which ultimately delegates to +`Continuation.yield()` to pause the carrier continuation object. + +The scheduler has a single `ContinuationScope` object. When a command is mounted, the scheduler will +create a new `Continuation` object bound to that scope, and a `Coroutine` object bound to the +continuation. `ContinuationScope` and `Continuation` are currently JDK-private classes; the build +needs to open the module to the wpilib/unnamed module for reflective access at compile and runtime. +Because access is entirely reflective, wrapper classes at the library level will be used to make +access easier. + +### Scheduling + +Scheduling a command with `Scheduler.schedule()` will add the command to a queue of pending +commands. Any command in the queue that conflicts and has a lower priority will be removed from the +queue without calling the `onCancel` hook. At the start of `Scheduler.run()`, all commands that +conflict with those in the queue are cancelled, then the queued commands are promoted to running. + +Scheduling an inner command will bypass the queue and immediately begin to run. This avoids delays +caused by loop timings for deeply nested commands. + +### Scheduler `run()` Cycle + +1. Poll the event loop for triggers (which may queue or cancel commands) +2. Run periodic sideload functions +3. Promote scheduled commands to running + 1. Cancels any running commands that conflict with scheduled ones +4. Iterate over running commands + 1. Mount + 2. Run until yield point is reached or an error is raised + 3. Unmount + 4. Evict if the command finished + 1. Any inner command still running is canceled +5. Schedule default commands for the next iteration to pick up and start running + +### Interruption + +* Caused by scheduling a command that requires resources already in use by one or more running + commands +* Results in cancellation of the conflicting commands + * Commands are moved to a pending-cancellation state + * Then when `run()` is next called, they are removed from the scheduler + * This occurs prior to the scheduled commands being promoted to the running state + * The conflicting command’s entire tree (all ancestors and children) will be cancelled +* Siblings in a composition can interrupt each other + * eg `fork(command1); fork(command2)`, where `command1` and `command2` share at least one + common requirement, would cause `command1` to be interrupted by `command2` + +### Telemetry + +Scheduler state is serialized using protobuf. The scheduler will send a list of the currently queued +commands and a list of the current running commands. Commands are serialized as (id: uint32, +parent_id: uint32, name: string, priority: int32, required_resources: string array). Consumers can +use the `id` and `parent_id` attributes to reconstruct the tree structure, if desired. `id` and +`parent_id` marginally increase the size of serialized data, but make the schema and deserialization +quite simple. From 10ff94f1d56faf7755d3c617b9b590cca05ebe8e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Apr 2025 09:35:48 -0400 Subject: [PATCH 013/153] Rename package to org.wpilib.commands3 --- commandsv3/CommandsV3.json | 2 +- commandsv3/build.gradle | 2 +- .../commandsv3 => org/wpilib/commands3}/Command.java | 2 +- .../wpilib/commands3}/CommandBuilder.java | 2 +- .../wpilib/commands3}/CommandExecutionException.java | 2 +- .../commandsv3 => org/wpilib/commands3}/CommandState.java | 2 +- .../commandsv3 => org/wpilib/commands3}/Continuation.java | 2 +- .../wpilib/commands3}/ContinuationScope.java | 2 +- .../commandsv3 => org/wpilib/commands3}/Coroutine.java | 2 +- .../commandsv3 => org/wpilib/commands3}/IdleCommand.java | 2 +- .../wpilib/commands3}/ParallelGroup.java | 2 +- .../wpilib/commands3}/RequireableResource.java | 2 +- .../commandsv3 => org/wpilib/commands3}/Scheduler.java | 4 ++-- .../commandsv3 => org/wpilib/commands3}/Sequence.java | 2 +- .../commandsv3 => org/wpilib/commands3}/WaitCommand.java | 2 +- .../wpilib/commands3}/button/CommandGenericHID.java | 4 ++-- .../wpilib/commands3}/button/CommandJoystick.java | 4 ++-- .../wpilib/commands3}/button/CommandPS4Controller.java | 4 ++-- .../wpilib/commands3}/button/CommandPS5Controller.java | 4 ++-- .../wpilib/commands3}/button/CommandStadiaController.java | 4 ++-- .../wpilib/commands3}/button/CommandXboxController.java | 4 ++-- .../wpilib/commands3}/button/InternalButton.java | 2 +- .../wpilib/commands3}/button/JoystickButton.java | 2 +- .../wpilib/commands3}/button/NetworkButton.java | 2 +- .../wpilib/commands3}/button/POVButton.java | 2 +- .../wpilib/commands3}/button/RobotModeTriggers.java | 2 +- .../wpilib/commands3}/button/Trigger.java | 6 +++--- .../wpilib/commands3}/proto/CommandProto.java | 6 +++--- .../wpilib/commands3}/proto/ProtobufCommand.java | 2 +- .../commands3}/proto/ProtobufRequireableResource.java | 2 +- .../wpilib/commands3}/proto/ProtobufScheduler.java | 2 +- .../wpilib/commands3}/proto/RequireableResourceProto.java | 4 ++-- .../wpilib/commands3}/proto/Scheduler.java | 2 +- .../wpilib/commands3}/proto/SchedulerProto.java | 4 ++-- commandsv3/src/main/proto/scheduler.proto | 2 +- .../wpilib/commands3}/CoroutineTest.java | 2 +- .../commandsv3 => org/wpilib/commands3}/NullCommand.java | 2 +- .../wpilib/commands3}/ParallelGroupTest.java | 2 +- .../wpilib/commands3}/SchedulerTest.java | 2 +- .../commandsv3 => org/wpilib/commands3}/SequenceTest.java | 2 +- .../wpilib/commands3}/button/TriggerTest.java | 8 ++++---- .../wpilibj/examples/coroutines/AsyncCommandBot.java | 6 +++--- .../edu/wpi/first/wpilibj/examples/coroutines/Robot.java | 4 ++-- .../wpilibj/examples/coroutines/subsystems/Drive.java | 4 ++-- .../wpilibj/examples/coroutines/subsystems/Intake.java | 4 ++-- .../examples/coroutines/subsystems/Pneumatics.java | 4 ++-- .../wpilibj/examples/coroutines/subsystems/Shooter.java | 2 +- .../wpilibj/examples/coroutines/subsystems/Storage.java | 6 +++--- 48 files changed, 72 insertions(+), 72 deletions(-) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/Command.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/CommandBuilder.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/CommandExecutionException.java (95%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/CommandState.java (95%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/Continuation.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/ContinuationScope.java (97%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/Coroutine.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/IdleCommand.java (97%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/ParallelGroup.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/RequireableResource.java (98%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/Scheduler.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/Sequence.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/WaitCommand.java (96%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandGenericHID.java (98%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandJoystick.java (98%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandPS4Controller.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandPS5Controller.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandStadiaController.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/CommandXboxController.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/InternalButton.java (97%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/JoystickButton.java (94%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/NetworkButton.java (97%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/POVButton.java (96%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/RobotModeTriggers.java (96%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/Trigger.java (98%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/CommandProto.java (91%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/ProtobufCommand.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/ProtobufRequireableResource.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/ProtobufScheduler.java (99%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/RequireableResourceProto.java (90%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/Scheduler.java (98%) rename commandsv3/src/main/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/proto/SchedulerProto.java (93%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/CoroutineTest.java (95%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/NullCommand.java (92%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/ParallelGroupTest.java (99%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/SchedulerTest.java (99%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/SequenceTest.java (98%) rename commandsv3/src/test/java/{edu/wpi/first/wpilibj/commandsv3 => org/wpilib/commands3}/button/TriggerTest.java (94%) diff --git a/commandsv3/CommandsV3.json b/commandsv3/CommandsV3.json index 015f7296a7c..8e79da97c51 100644 --- a/commandsv3/CommandsV3.json +++ b/commandsv3/CommandsV3.json @@ -8,7 +8,7 @@ "jsonUrl": "", "javaDependencies": [ { - "groupId": "edu.wpi.first.commandsv3", + "groupId": "org.wpilib.commands3", "artifactId": "commandsv3-java", "version": "wpilib" } diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index d6fb4d0537d..7d3b685f84c 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -2,7 +2,7 @@ ext { useJava = true useCpp = false baseId = 'commandsv3' - groupId = 'edu.wpi.first.wpilibj' + groupId = 'org.wpilib' nativeName = 'commandsv3' devMain = '' diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java rename to commandsv3/src/main/java/org/wpilib/commands3/Command.java index 63687f18aaa..e001abae03b 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import edu.wpi.first.units.measure.Time; import java.util.Collections; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java rename to commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 55d9696344a..2bea35a939e 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java similarity index 95% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java rename to commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java index 88260885e30..39e9468f2f1 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandExecutionException.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; /** * An exception thrown when a {@link Command} encounters an error while running in a {@link diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java similarity index 95% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java rename to commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index bda4975be36..6d8a3fea814 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; /** * Represents the state of a command as it is executed by the scheduler. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java rename to commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 3b7c9cf1eb7..80d96d197a3 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import java.lang.invoke.MethodHandle; import java.lang.invoke.MethodHandles; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java similarity index 97% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java rename to commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index 9f251138ff8..3c8a6ba9994 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import java.lang.invoke.MethodHandle; import java.lang.invoke.MethodHandles; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java rename to commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 36d78e364f3..354009ddf0a 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import edu.wpi.first.units.measure.Time; import java.util.Arrays; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java similarity index 97% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java rename to commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index 33e922b1736..e0577725c32 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java rename to commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index ec164b7be13..074dc81061d 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java similarity index 98% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java rename to commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index b79f38f745e..c18a35ddfc6 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import edu.wpi.first.units.measure.Time; import edu.wpi.first.util.sendable.Sendable; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java rename to commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index f78600aaebd..5f29089acb5 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -2,11 +2,11 @@ // 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.commandsv3; +package org.wpilib.commands3; import edu.wpi.first.util.protobuf.ProtobufSerializable; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.commandsv3.proto.SchedulerProto; +import org.wpilib.commands3.proto.SchedulerProto; import edu.wpi.first.wpilibj.event.EventLoop; import java.util.ArrayList; import java.util.Collection; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java rename to commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 567b8c79c90..960aeeb22e8 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java similarity index 96% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java rename to commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java index 2c42d1c6bea..d3277abd8bd 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/WaitCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java similarity index 98% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 70d3ac670f3..4a7e8140320 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.GenericHID; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link GenericHID} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java similarity index 98% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java index a921159dfeb..5d13c4c9e6e 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandJoystick.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link Joystick} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index 6d50ed70a9a..2e0b512bf46 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS4Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.PS4Controller; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link PS4Controller} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 5897fc324b9..056e8466580 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandPS5Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.PS5Controller; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link PS5Controller} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java index 0ec634eb97b..0f85fdc83a8 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandStadiaController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.StadiaController; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link StadiaController} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java index c2b05d76156..a5e465970c3 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/CommandXboxController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -2,10 +2,10 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.XboxController; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; /** * A version of {@link XboxController} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java similarity index 97% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java index 71cbff8c9af..a82ffe17f07 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/InternalButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java @@ -2,7 +2,7 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import java.util.concurrent.atomic.AtomicBoolean; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java similarity index 94% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java index ec90ce6d180..b5d5b38517e 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/JoystickButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java @@ -2,7 +2,7 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java similarity index 97% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java index d3b9e447cf3..b49434f95ed 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/NetworkButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java @@ -2,7 +2,7 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java similarity index 96% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java index c29202eb628..cfe843695c4 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/POVButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java @@ -2,7 +2,7 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java b/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java similarity index 96% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java index 5f28e793e56..abc8c101124 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/RobotModeTriggers.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java @@ -2,7 +2,7 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.DriverStation; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java similarity index 98% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java rename to commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java index 0f078612f9d..b7f6286ad12 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/button/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java @@ -2,15 +2,15 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.units.measure.Time; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.Scheduler; import edu.wpi.first.wpilibj.event.EventLoop; import java.util.ArrayList; import java.util.EnumMap; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java similarity index 91% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index ceb1ede8ae9..281e81a7381 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -2,11 +2,11 @@ // 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.commandsv3.proto; +package org.wpilib.commands3.proto; import edu.wpi.first.util.protobuf.Protobuf; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.Scheduler; import us.hebi.quickbuf.Descriptors; public class CommandProto implements Protobuf { diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java index 8af72b66909..3191d1d44f3 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java @@ -3,7 +3,7 @@ // the WPILib BSD license file in the root directory of this project. // Code generated by protocol buffer compiler. Do not edit! -package edu.wpi.first.wpilibj.commandsv3.proto; +package org.wpilib.commands3.proto; import java.io.IOException; import us.hebi.quickbuf.Descriptors; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java index cc95122d693..1fa523208ff 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufRequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java @@ -3,7 +3,7 @@ // the WPILib BSD license file in the root directory of this project. // Code generated by protocol buffer compiler. Do not edit! -package edu.wpi.first.wpilibj.commandsv3.proto; +package org.wpilib.commands3.proto; import java.io.IOException; import us.hebi.quickbuf.Descriptors; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java similarity index 99% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java index 4f93f284ca0..d8a95813c40 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/ProtobufScheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java @@ -3,7 +3,7 @@ // the WPILib BSD license file in the root directory of this project. // Code generated by protocol buffer compiler. Do not edit! -package edu.wpi.first.wpilibj.commandsv3.proto; +package org.wpilib.commands3.proto; import java.io.IOException; import us.hebi.quickbuf.Descriptors; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java similarity index 90% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java index 6a80a3a5799..4084fca0451 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/RequireableResourceProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java @@ -2,10 +2,10 @@ // 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.commandsv3.proto; +package org.wpilib.commands3.proto; import edu.wpi.first.util.protobuf.Protobuf; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import org.wpilib.commands3.RequireableResource; import us.hebi.quickbuf.Descriptors; public class RequireableResourceProto diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java similarity index 98% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java index b4eb075335b..d21fa770c95 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java @@ -3,7 +3,7 @@ // the WPILib BSD license file in the root directory of this project. // Code generated by protocol buffer compiler. Do not edit! -package edu.wpi.first.wpilibj.commandsv3.proto; +package org.wpilib.commands3.proto; import us.hebi.quickbuf.Descriptors; import us.hebi.quickbuf.ProtoUtil; diff --git a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java similarity index 93% rename from commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java rename to commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java index a7aabb156b0..ab68c4f02de 100644 --- a/commandsv3/src/main/java/edu/wpi/first/wpilibj/commandsv3/proto/SchedulerProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java @@ -2,10 +2,10 @@ // 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.commandsv3.proto; +package org.wpilib.commands3.proto; import edu.wpi.first.util.protobuf.Protobuf; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Scheduler; import us.hebi.quickbuf.Descriptors; public class SchedulerProto implements Protobuf { diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/scheduler.proto index e05e3e40308..bbeed7a5351 100644 --- a/commandsv3/src/main/proto/scheduler.proto +++ b/commandsv3/src/main/proto/scheduler.proto @@ -2,7 +2,7 @@ syntax = "proto3"; package wpi.proto; -option java_package = "edu.wpi.first.wpilibj.commandsv3.proto"; +option java_package = "org.wpilib.commands3.proto"; option java_multiple_files = true; /* diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java similarity index 95% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index ae910b4db95..c056aa59253 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.assertTrue; diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java b/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java similarity index 92% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java rename to commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java index 93176695c2b..c3f8429db25 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/NullCommand.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import java.util.Set; diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java similarity index 99% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 4ae2767c4f5..9b35242caab 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.*; diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java similarity index 99% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index a42d20b3d7c..f02d5b7a4c7 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java similarity index 98% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java index 6694486b76d..3d1869cea76 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/SequenceTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java @@ -2,7 +2,7 @@ // 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.commandsv3; +package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; diff --git a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java similarity index 94% rename from commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java index 89dfef772da..733fbc35881 100644 --- a/commandsv3/src/test/java/edu/wpi/first/wpilibj/commandsv3/button/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java @@ -2,14 +2,14 @@ // 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.commandsv3.button; +package org.wpilib.commands3.button; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.Coroutine; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.Coroutine; +import org.wpilib.commands3.Scheduler; import java.util.concurrent.atomic.AtomicBoolean; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java index b7c44efc1e4..fdb00185038 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java @@ -4,9 +4,9 @@ package edu.wpi.first.wpilibj.examples.coroutines; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.button.CommandXboxController; -import edu.wpi.first.wpilibj.commandsv3.button.Trigger; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.button.CommandXboxController; +import org.wpilib.commands3.button.Trigger; import edu.wpi.first.wpilibj.examples.coroutines.Constants.AutoConstants; import edu.wpi.first.wpilibj.examples.coroutines.Constants.OIConstants; import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java index 9248f1848a9..54e901d6696 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java @@ -5,8 +5,8 @@ package edu.wpi.first.wpilibj.examples.coroutines; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.Scheduler; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.Scheduler; /** * The VM is configured to automatically run this class, and to call the functions corresponding to diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java index 23082e84532..d0264d8c41c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java @@ -9,8 +9,8 @@ import edu.wpi.first.units.measure.Distance; import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.RequireableResource; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.coroutines.Constants.DriveConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java index a8d74fa2758..57ca1860828 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java @@ -8,8 +8,8 @@ import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.PneumaticsModuleType; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.RequireableResource; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; public class Intake extends RequireableResource { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java index 9798519a431..aeb1b1b2962 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java @@ -7,8 +7,8 @@ import edu.wpi.first.wpilibj.AnalogPotentiometer; import edu.wpi.first.wpilibj.Compressor; import edu.wpi.first.wpilibj.PneumaticsModuleType; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.RequireableResource; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; /** Subsystem for managing the compressor, pressure sensor, etc. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java index 14ede9d40aa..844bf9dbc08 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java @@ -11,7 +11,7 @@ import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; +import org.wpilib.commands3.RequireableResource; import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java index 70f8a168b1f..7f26f19402c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java @@ -5,9 +5,9 @@ package edu.wpi.first.wpilibj.examples.coroutines.subsystems; import edu.wpi.first.wpilibj.DigitalInput; -import edu.wpi.first.wpilibj.commandsv3.Command; -import edu.wpi.first.wpilibj.commandsv3.RequireableResource; -import edu.wpi.first.wpilibj.commandsv3.button.Trigger; +import org.wpilib.commands3.Command; +import org.wpilib.commands3.RequireableResource; +import org.wpilib.commands3.button.Trigger; import edu.wpi.first.wpilibj.examples.coroutines.Constants.StorageConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; From 841319da0d2b404dc04556d1c6250e6c71be5c1b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Apr 2025 18:32:51 -0400 Subject: [PATCH 014/153] Allow child commands to interrupt their siblings But not interrupt their parents when doing so --- .../java/org/wpilib/commands3/Coroutine.java | 38 +++++++++++++++++ .../java/org/wpilib/commands3/Scheduler.java | 42 +++---------------- .../org/wpilib/commands3/SchedulerTest.java | 40 ++++++++++-------- 3 files changed, 66 insertions(+), 54 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 354009ddf0a..6dedabf6fd3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -8,6 +8,7 @@ import java.util.Arrays; import java.util.Collection; import java.util.function.Consumer; +import java.util.stream.Collectors; /** * A coroutine object is injected into command's {@link Command#run(Coroutine)} method to allow @@ -102,6 +103,8 @@ public void await(Command command) { * @throws IllegalArgumentException if any of the commands conflict with each other */ public void awaitAll(Collection commands) { + validateNoConflicts(commands); + // Schedule anything that's not already queued or running for (var command : commands) { if (!scheduler.isScheduledOrRunning(command)) { @@ -135,6 +138,8 @@ public void awaitAll(Command... commands) { * @throws IllegalArgumentException if any of the commands conflict with each other */ public void awaitAny(Collection commands) { + validateNoConflicts(commands); + // Schedule anything that's not already queued or running for (var command : commands) { if (!scheduler.isScheduledOrRunning(command)) { @@ -158,6 +163,39 @@ public void awaitAny(Command... commands) { awaitAny(Arrays.asList(commands)); } + /** + * Validates that a set of commands have no internal requirement conflicts. An error is thrown if + * a conflict is detected. + * + * @param commands The commands to validate + * @throws IllegalArgumentException If at least one pair of commands is found in the input + * where both commands have at least one required resource in common + */ + private static void validateNoConflicts(Collection commands) { + for (var c1 : commands) { + for (var c2 : commands) { + if (c1 == c2) { + // Commands can't conflict with themselves + continue; + } + + // TODO: Report all pairs of conflicting commands? Instead of just the first one we find + if (c1.conflictsWith(c2)) { + var conflictNames = + c1.requirements().stream() + .filter(c2::requires) + .map(RequireableResource::getName) + .collect(Collectors.joining(", ")); + + throw new IllegalArgumentException( + "Command %s requires resources that are already used by %s. Both require %s" + .formatted(c2.name(), c1.name(), conflictNames) + ); + } + } + } + } + /** * Waits for some duration of time to elapse. Returns immediately if the given duration is zero or * negative. Call this within a command or command composition to introduce a simple delay. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 5f29089acb5..95917622c12 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -184,26 +184,6 @@ public ScheduleResult schedule(Command command) { return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; } - // If scheduled within a composition, prevent the composition from scheduling multiple - // conflicting commands - // TODO: Should we return quietly instead of throwing an exception? - // Should we cancel the sibling? - var siblings = potentialSiblings(); - var conflictingSibling = siblings.stream().filter(command::conflictsWith).findFirst(); - if (conflictingSibling.isPresent()) { - var conflicts = new ArrayList<>(command.requirements()); - conflicts.retainAll(conflictingSibling.get().requirements()); - throw new IllegalArgumentException( - "Command " - + command.name() - + " requires resources that are already used by " - + conflictingSibling.get().name() - + ". Both require " - + conflicts.stream() - .map(RequireableResource::getName) - .collect(Collectors.joining(", "))); - } - for (var scheduledState : onDeck) { if (!command.conflictsWith(scheduledState.command())) { // No shared requirements, skip @@ -259,22 +239,6 @@ private boolean isSchedulable(Command command) { return true; } - private Collection potentialSiblings() { - var siblings = new ArrayList(); - for (var state : commandStates.values()) { - if (state.parent() != null && state.parent() == currentCommand()) { - siblings.add(state.command()); - } - } - for (var state : onDeck) { - if (state.parent() != null && state.parent() == currentCommand()) { - siblings.add(state.command()); - } - } - - return siblings; - } - private void evictConflictingOnDeckCommands(Command command) { for (var iterator = onDeck.iterator(); iterator.hasNext(); ) { var scheduledState = iterator.next(); @@ -300,8 +264,12 @@ private void evictConflictingRunningCommands(CommandState incomingState) { .filter(state -> !inheritsFrom(incomingState, state.command())) .map( state -> { + // Find the highest level ancestor of the conflicting command from which the + // incoming state does _not_ inherit. If they're totally unrelated, this will + // get the very root ancestor; otherwise, it'll return a direct sibling of the + // incoming command CommandState root = state; - while (root.parent() != null) { + while (root.parent() != null && root.parent() != incomingState.parent()) { root = commandStates.get(root.parent()); } return root; diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index f02d5b7a4c7..bb2de2de463 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -646,29 +646,35 @@ void protobuf() { } @Test - void siblingsInCompositionCannotShareRequirements() { + void siblingsInCompositionCanShareRequirements() { var resource = new RequireableResource("The Resource", scheduler); + var firstRan = new AtomicBoolean(false); + var secondRan = new AtomicBoolean(false); + + var first = resource.run(c -> { + firstRan.set(true); + c.park(); + }).named("First"); + + var second = resource.run(c -> { + secondRan.set(true); + c.park(); + }).named("Second"); + var group = Command.noRequirements(co -> { - co.fork(resource.run(Coroutine::park).named("First")); - co.fork(resource.run(Coroutine::park).named("Second")); + co.fork(first); + co.fork(second); + co.park(); }).named("Group"); scheduler.schedule(group); + scheduler.run(); - try { - scheduler.run(); - fail("An error should have been thrown"); - } catch (CommandExecutionException e) { - assertEquals(group, e.getCommand()); - if (e.getCause() instanceof IllegalArgumentException argumentException) { - assertEquals( - "Command Second requires resources that are already used by First. " - + "Both require The Resource", - argumentException.getMessage()); - } else { - fail("Unexpected cause: " + e.getCause()); - } - } + assertTrue(firstRan.get(), "First child should have run to a yield point"); + assertTrue(secondRan.get(), "Second child should have run to a yield point"); + assertFalse(scheduler.isScheduledOrRunning(first), "First child should have been interrupted"); + assertTrue(scheduler.isRunning(second), "Second child should still be running"); + assertTrue(scheduler.isRunning(group), "Group should still be running"); } @Test From 62d1b66490ea9b5190c5dbcc2237b86f2892124b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Apr 2025 19:29:29 -0400 Subject: [PATCH 015/153] Remove CommandExecutionException No longer necessary (was useful in a thread-based model, not in a coroutine one) --- .../commands3/CommandExecutionException.java | 34 ------------------- .../java/org/wpilib/commands3/Scheduler.java | 11 +----- .../org/wpilib/commands3/SchedulerTest.java | 26 ++++---------- .../java/edu/wpi/first/wpilibj/RobotBase.java | 7 ---- 4 files changed, 8 insertions(+), 70 deletions(-) delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.java deleted file mode 100644 index 39e9468f2f1..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandExecutionException.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 org.wpilib.commands3; - -/** - * An exception thrown when a {@link Command} encounters an error while running in a {@link - * Scheduler}. - */ -public class CommandExecutionException extends RuntimeException { - /** The command that had the exception. */ - private final Command command; - - /** - * Creates a new CommandExecutionException. - * - * @param command the command that encountered the exception - * @param cause the exception itself - */ - public CommandExecutionException(Command command, Throwable cause) { - super("An exception was detected while running command " + command.name(), cause); - this.command = command; - } - - /** - * Gets the command that encountered the exception. - * - * @return the command - */ - public Command getCommand() { - return command; - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 95917622c12..06164fd3968 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -493,16 +493,7 @@ private void removeOrphanedChildren(Command parent) { * @return the binding coroutine */ private Coroutine buildCoroutine(Command command) { - return new Coroutine( - this, - scope, - coroutine -> { - try { - command.run(coroutine); - } catch (Exception e) { - throw new CommandExecutionException(command, e); - } - }); + return new Coroutine(this, scope, command::run); } /** diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index bb2de2de463..1a57e3f46e1 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -164,23 +164,13 @@ void errorDetection() { scheduler.schedule(command); try { + scheduler.run(); fail("An exception should have been thrown"); - } catch (CommandExecutionException e) { - if (e.getCommand() != command) { - fail("Expected command " + command + ", but was " + e.getCommand()); - } - - var cause = e.getCause(); - if (cause instanceof RuntimeException re) { - assertEquals("The exception", re.getMessage()); - } else { - fail( - "Expected cause to be a RuntimeException with message 'The exception', but was " - + cause); - } + } catch (RuntimeException e) { + assertEquals("The exception", e.getMessage()); } catch (Throwable t) { - fail("Expected a CommandExecutionException to be thrown, but got " + t); + fail("Expected a RuntimeException to be thrown, but got " + t); } } @@ -428,14 +418,12 @@ void compositionsCannotAwaitConflictingCommands() { try { scheduler.run(); fail("An exception should have been thrown"); - } catch (CommandExecutionException e) { - if (e.getCause() instanceof IllegalArgumentException iae) { + } catch (IllegalArgumentException iae) { assertEquals( "Command Second requires resources that are already used by First. Both require The Resource", iae.getMessage()); - } else { - fail("Unexpected exception: " + e); - } + } catch (Exception e) { + fail("Unexpected exception: " + e); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 0b8e4fb86a4..61c96bd6a69 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -296,13 +296,6 @@ private static void runRobot(Supplier robotSupplier) { try { robot.startCompetition(); } catch (Throwable throwable) { - // TODO: This can do some weird things with the command framework. - // An exception thrown during a command's execution will be wrapped and rethrown as a - // CommandExecutionException, with the cause being that original exception (which may - // in turn also have a cause, etc). - // This bit of code means that an exception thrown by a method called within a command - // will be reported differently than that same exception when called outside a command - // TODO: Should we just report every error up the stack, instead of only the first level? Throwable cause = throwable.getCause(); if (cause != null) { throwable = cause; From 9373371cc871367f81c22f11133e6308ad1fb5cd Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Apr 2025 07:42:51 -0400 Subject: [PATCH 016/153] Move parallel and sequence builders to top-level classes --- .../java/org/wpilib/commands3/Command.java | 14 +- .../org/wpilib/commands3/ParallelGroup.java | 130 +---------------- .../commands3/ParallelGroupBuilder.java | 136 ++++++++++++++++++ .../java/org/wpilib/commands3/Sequence.java | 73 +--------- .../org/wpilib/commands3/SequenceBuilder.java | 78 ++++++++++ 5 files changed, 229 insertions(+), 202 deletions(-) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index e001abae03b..52e591e3b2e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -240,7 +240,7 @@ static CommandBuilder requiring(RequireableResource requirement, RequireableReso * @param commands The commands to run in parallel * @return A command builder */ - static ParallelGroup.Builder parallel(Command... commands) { + static ParallelGroupBuilder parallel(Command... commands) { return ParallelGroup.all(commands); } @@ -252,7 +252,7 @@ static ParallelGroup.Builder parallel(Command... commands) { * @param commands The commands to run in parallel * @return A command builder */ - static ParallelGroup.Builder race(Command... commands) { + static ParallelGroupBuilder race(Command... commands) { return ParallelGroup.race(commands); } @@ -264,7 +264,7 @@ static ParallelGroup.Builder race(Command... commands) { * @param commands The commands to run in sequence. * @return A command builder */ - static Sequence.Builder sequence(Command... commands) { + static SequenceBuilder sequence(Command... commands) { return Sequence.sequence(commands); } @@ -285,7 +285,7 @@ static CommandBuilder waitingFor(BooleanSupplier condition) { }); } - default ParallelGroup.Builder until(BooleanSupplier endCondition) { + default ParallelGroupBuilder until(BooleanSupplier endCondition) { return ParallelGroup.builder() .optional(this, Command.waitingFor(endCondition).named("Until Condition")); } @@ -307,7 +307,7 @@ default ParallelGroup.Builder until(BooleanSupplier endCondition) { * @param next The command to run after this one in the sequence * @return A sequence builder */ - default Sequence.Builder andThen(Command next) { + default SequenceBuilder andThen(Command next) { return Sequence.builder().andThen(this).andThen(next); } @@ -327,7 +327,7 @@ default Sequence.Builder andThen(Command next) { * @param parallel The commands to run in parallel with this one * @return A parallel group builder */ - default ParallelGroup.Builder alongWith(Command... parallel) { + default ParallelGroupBuilder alongWith(Command... parallel) { return ParallelGroup.builder().requiring(this).requiring(parallel); } @@ -338,7 +338,7 @@ default ParallelGroup.Builder alongWith(Command... parallel) { * @param parallel The commands to run in parallel with this one * @return A parallel group builder */ - default ParallelGroup.Builder raceWith(Command... parallel) { + default ParallelGroupBuilder raceWith(Command... parallel) { return ParallelGroup.builder().optional(this).optional(parallel); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 074dc81061d..9b2ccd783f5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -6,13 +6,10 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import java.util.Arrays; import java.util.Collection; import java.util.HashSet; import java.util.LinkedHashSet; import java.util.Set; -import java.util.function.BooleanSupplier; -import java.util.stream.Collectors; /** * A type of command that runs multiple other commands in parallel. The group will end after all @@ -98,7 +95,7 @@ public ParallelGroup( * @param commands the commands to run in parallel * @return the group */ - public static Builder race(Command... commands) { + public static ParallelGroupBuilder race(Command... commands) { return builder().optional(commands); } @@ -109,7 +106,7 @@ public static Builder race(Command... commands) { * @param commands the commands to run in parallel * @return the group */ - public static Builder all(Command... commands) { + public static ParallelGroupBuilder all(Command... commands) { return builder().requiring(commands); } @@ -153,126 +150,7 @@ public String toString() { return "ParallelGroup[name=" + name + "]"; } - public static Builder builder() { - return new Builder(); - } - - public static class Builder { - private final Set commands = new LinkedHashSet<>(); - private final Set requiredCommands = new LinkedHashSet<>(); - private BooleanSupplier endCondition = null; - - /** - * Adds one or more optional commands to the group. They will not be required to complete for - * the parallel group to exit, and will be canceled once all required commands have finished. - * - * @param commands The optional commands to add to the group - * @return The builder object, for chaining - */ - public Builder optional(Command... commands) { - this.commands.addAll(Arrays.asList(commands)); - return this; - } - - /** - * Adds one or more required commands to the group. All required commands will need to complete - * for the group to exit. - * - * @param commands The required commands to add to the group - * @return The builder object, for chaining - */ - public Builder requiring(Command... commands) { - requiredCommands.addAll(Arrays.asList(commands)); - this.commands.addAll(requiredCommands); - return this; - } - - /** - * Forces the group to be a pure race, where the group will finish after the first command in - * the group completes. All other commands in the group will be canceled. - * - * @return The builder object, for chaining - */ - public Builder racing() { - requiredCommands.clear(); - return this; - } - - /** - * Forces the group to require all its commands to complete, overriding any configured race or - * deadline behaviors. The group will only exit once every command has completed. - * - * @return The builder object, for chaining - */ - public Builder requireAll() { - requiredCommands.clear(); - requiredCommands.addAll(commands); - return this; - } - - /** - * Adds an end condition to the command group. If this condition is met before all required - * commands have completed, the group will exit early. If multiple end conditions are added - * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end - * condition added will be used and any previously configured condition will be overridden. - * - * @param condition The end condition for the group - * @return The builder object, for chaining - */ - public Builder until(BooleanSupplier condition) { - endCondition = condition; - return this; - } - - /** - * Creates the group, using the provided named. The group will require everything that the - * commands in the group require, and will have a priority level equal to the highest priority - * among those commands. - * - * @param name The name of the parallel group - * @return The built group - */ - public ParallelGroup named(String name) { - var group = new ParallelGroup(name, commands, requiredCommands); - if (endCondition == null) { - // No custom end condition, return the group as is - return group; - } - - // We have a custom end condition, so we need to wrap the group in a race - return builder() - .optional(group, Command.waitingFor(endCondition).named("Until Condition")) - .named(name); - } - - /** - * Creates the group, giving it a name based on the commands within the group. - * - * @return The built group - */ - public ParallelGroup withAutomaticName() { - // eg "(CommandA & CommandB & CommandC)" - String required = - requiredCommands.stream().map(Command::name).collect(Collectors.joining(" & ", "(", ")")); - - var optionalCommands = new LinkedHashSet<>(commands); - optionalCommands.removeAll(requiredCommands); - // eg "(CommandA | CommandB | CommandC)" - String optional = - optionalCommands.stream().map(Command::name).collect(Collectors.joining(" | ", "(", ")")); - - if (requiredCommands.isEmpty()) { - // No required commands, pure race - return named(optional); - } else if (optionalCommands.isEmpty()) { - // Everything required - return named(required); - } else { - // Some form of deadline - // eg "[(CommandA & CommandB) * (CommandX | CommandY | ...)]" - String name = "[%s * %s]".formatted(required, optional); - return named(name); - } - } + public static ParallelGroupBuilder builder() { + return new ParallelGroupBuilder(); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java new file mode 100644 index 00000000000..58f563186ca --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -0,0 +1,136 @@ +// 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 org.wpilib.commands3; + +import java.util.Arrays; +import java.util.LinkedHashSet; +import java.util.Set; +import java.util.function.BooleanSupplier; +import java.util.stream.Collectors; + +/** + * A builder class to configure and then create a {@link ParallelGroup}. Like + * {@link CommandBuilder}, the final command is created by calling the terminal + * {@link #named(String)} method, or with an automatically generated name using + * {@link #withAutomaticName()}. + */ +public class ParallelGroupBuilder { + private final Set commands = new LinkedHashSet<>(); + private final Set requiredCommands = new LinkedHashSet<>(); + private BooleanSupplier endCondition = null; + + /** + * Adds one or more optional commands to the group. They will not be required to complete for + * the parallel group to exit, and will be canceled once all required commands have finished. + * + * @param commands The optional commands to add to the group + * @return The builder object, for chaining + */ + public ParallelGroupBuilder optional(Command... commands) { + this.commands.addAll(Arrays.asList(commands)); + return this; + } + + /** + * Adds one or more required commands to the group. All required commands will need to complete + * for the group to exit. + * + * @param commands The required commands to add to the group + * @return The builder object, for chaining + */ + public ParallelGroupBuilder requiring(Command... commands) { + requiredCommands.addAll(Arrays.asList(commands)); + this.commands.addAll(requiredCommands); + return this; + } + + /** + * Forces the group to be a pure race, where the group will finish after the first command in + * the group completes. All other commands in the group will be canceled. + * + * @return The builder object, for chaining + */ + public ParallelGroupBuilder racing() { + requiredCommands.clear(); + return this; + } + + /** + * Forces the group to require all its commands to complete, overriding any configured race or + * deadline behaviors. The group will only exit once every command has completed. + * + * @return The builder object, for chaining + */ + public ParallelGroupBuilder requireAll() { + requiredCommands.clear(); + requiredCommands.addAll(commands); + return this; + } + + /** + * Adds an end condition to the command group. If this condition is met before all required + * commands have completed, the group will exit early. If multiple end conditions are added + * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end + * condition added will be used and any previously configured condition will be overridden. + * + * @param condition The end condition for the group + * @return The builder object, for chaining + */ + public ParallelGroupBuilder until(BooleanSupplier condition) { + endCondition = condition; + return this; + } + + /** + * Creates the group, using the provided named. The group will require everything that the + * commands in the group require, and will have a priority level equal to the highest priority + * among those commands. + * + * @param name The name of the parallel group + * @return The built group + */ + public ParallelGroup named(String name) { + var group = new ParallelGroup(name, commands, requiredCommands); + if (endCondition == null) { + // No custom end condition, return the group as is + return group; + } + + // We have a custom end condition, so we need to wrap the group in a race + return ParallelGroup.builder() + .optional(group, Command.waitingFor(endCondition).named("Until Condition")) + .named(name); + } + + /** + * Creates the group, giving it a name based on the commands within the group. + * + * @return The built group + */ + public ParallelGroup withAutomaticName() { + // eg "(CommandA & CommandB & CommandC)" + String required = + requiredCommands.stream().map(Command::name).collect(Collectors.joining(" & ", "(", ")")); + + var optionalCommands = new LinkedHashSet<>(commands); + optionalCommands.removeAll(requiredCommands); + // eg "(CommandA | CommandB | CommandC)" + String optional = + optionalCommands.stream().map(Command::name).collect(Collectors.joining(" | ", "(", ")")); + + if (requiredCommands.isEmpty()) { + // No required commands, pure race + return named(optional); + } else if (optionalCommands.isEmpty()) { + // Everything required + return named(required); + } else { + // Some form of deadline + // eg "[(CommandA & CommandB) * (CommandX | CommandY | ...)]" + String name = "[%s * %s]".formatted(required, optional); + return named(name); + } + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 960aeeb22e8..82cdf143f0b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -4,14 +4,10 @@ package org.wpilib.commands3; -import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; - import java.util.ArrayList; import java.util.HashSet; import java.util.List; import java.util.Set; -import java.util.function.BooleanSupplier; -import java.util.stream.Collectors; /** * A sequence of commands that run one after another. Each successive command only starts after its @@ -83,12 +79,12 @@ public RobotDisabledBehavior robotDisabledBehavior() { return robotDisabledBehavior; } - public static Builder builder() { - return new Builder(); + public static SequenceBuilder builder() { + return new SequenceBuilder(); } - public static Builder sequence(Command... commands) { - var builder = new Builder(); + public static SequenceBuilder sequence(Command... commands) { + var builder = new SequenceBuilder(); for (var command : commands) { builder.andThen(command); } @@ -98,65 +94,4 @@ public static Builder sequence(Command... commands) { public static Command of(Command... commands) { return sequence(commands).withAutomaticName(); } - - public static final class Builder { - private final List steps = new ArrayList<>(); - private BooleanSupplier endCondition = null; - - /** - * Adds a command to the sequence. - * - * @param next The next command in the sequence - * @return The builder object, for chaining - */ - public Builder andThen(Command next) { - requireNonNullParam(next, "next", "Sequence.Builder.andThen"); - - steps.add(next); - return this; - } - - /** - * Adds an end condition to the command group. If this condition is met before all required - * commands have completed, the group will exit early. If multiple end conditions are added - * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end - * condition added will be used and any previously configured condition will be overridden. - * - * @param condition The end condition for the group - * @return The builder object, for chaining - */ - public Builder until(BooleanSupplier endCondition) { - this.endCondition = endCondition; - return this; - } - - /** - * Creates the sequence command, giving it the specified name. - * - * @param name The name of the sequence command - * @return The built command - */ - public Command named(String name) { - var seq = new Sequence(name, steps); - if (endCondition != null) { - // No custom end condition, return the group as is - return seq; - } - - // We have a custom end condition, so we need to wrap the group in a race - return ParallelGroup.builder() - .optional(seq, Command.waitingFor(endCondition).named("Until Condition")) - .named(name); - } - - /** - * Creates the sequence command, giving it an automatically generated name based on the commands - * in the sequence. - * - * @return The built command - */ - public Command withAutomaticName() { - return named(steps.stream().map(Command::name).collect(Collectors.joining(" -> "))); - } - } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java new file mode 100644 index 00000000000..7bff4d5fc56 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -0,0 +1,78 @@ +// 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 org.wpilib.commands3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.ArrayList; +import java.util.List; +import java.util.function.BooleanSupplier; +import java.util.stream.Collectors; + +/** + * A builder class to configure and then create a {@link Sequence}. Like {@link CommandBuilder}, + * the final command is created by calling the terminal {@link #named(String)} method, or with + * an automatically generated name using {@link #withAutomaticName()}. + */ +public class SequenceBuilder { + private final List steps = new ArrayList<>(); + private BooleanSupplier endCondition = null; + + /** + * Adds a command to the sequence. + * + * @param next The next command in the sequence + * @return The builder object, for chaining + */ + public SequenceBuilder andThen(Command next) { + requireNonNullParam(next, "next", "Sequence.Builder.andThen"); + + steps.add(next); + return this; + } + + /** + * Adds an end condition to the command group. If this condition is met before all required + * commands have completed, the group will exit early. If multiple end conditions are added + * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end + * condition added will be used and any previously configured condition will be overridden. + * + * @param condition The end condition for the group + * @return The builder object, for chaining + */ + public SequenceBuilder until(BooleanSupplier endCondition) { + this.endCondition = endCondition; + return this; + } + + /** + * Creates the sequence command, giving it the specified name. + * + * @param name The name of the sequence command + * @return The built command + */ + public Command named(String name) { + var seq = new Sequence(name, steps); + if (endCondition != null) { + // No custom end condition, return the group as is + return seq; + } + + // We have a custom end condition, so we need to wrap the group in a race + return ParallelGroup.builder() + .optional(seq, Command.waitingFor(endCondition).named("Until Condition")) + .named(name); + } + + /** + * Creates the sequence command, giving it an automatically generated name based on the commands + * in the sequence. + * + * @return The built command + */ + public Command withAutomaticName() { + return named(steps.stream().map(Command::name).collect(Collectors.joining(" -> "))); + } +} From 1d633440b6d56cebff9876a4fa7b756c3623df7f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Apr 2025 09:51:13 -0400 Subject: [PATCH 017/153] Update design doc telemetry and child command sections --- design-docs/commands-v3.md | 33 +++++++++++++++++++++++++++++++++ 1 file changed, 33 insertions(+) diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index e11106e2f58..a059d41ef5d 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -92,6 +92,11 @@ does not require that inner resource. Using the above example, directly scheduli requires `innerResource` will cancel a running `outerCommand` - but only if `outerCommand` is *currently using* the inner resource at the time. +**Effectively, all child commands in v3 are "proxied"**, using the v2 framework's definition, unless +using the built-in ParallelGroup and Sequence compositions or explicitly adding child command +requirements to the parent. However, child commands _cannot_ interrupt their parent, even if they +share requirements, unlike proxy commands in v2. + ### Priority Levels Priority levels allow for finer-grained control over when commands should be interruptible than a @@ -303,3 +308,31 @@ parent_id: uint32, name: string, priority: int32, required_resources: string arr use the `id` and `parent_id` attributes to reconstruct the tree structure, if desired. `id` and `parent_id` marginally increase the size of serialized data, but make the schema and deserialization quite simple. + +Command IDs are the Java system identity hashcode (_not_ object hashcode, which can be overridden +and be identical for different command objects). If a command has no parent, its parent ID will be +set to zero. + +Records in the serialized output will be ordered by scheduling order. As a result, child commands +will always appear _after_ their parent. + +For example, if a scheduler is running a command like this: + +```java +RequireableResource r1, r2; + +Command theCommand() { + return ParallelGroup.all( + r1.run(/* ... */).withPriority(1).named("Command 1"), + r2.run(/* ... */).withPriority(2).named("Command 2") + ).withAutomaticName(); +} +``` + +Telemetry for the scheduler would look like: + +| `id` | `parent_id` | `name` | `priority` | `required_resources` | +|--------|-------------|---------------------------|------------|----------------------| +| 347123 | 0 | "(Command 1 & Command 2)" | 2 | ["R1", "R2"] | +| 998712 | 347123 | "Command 1" | 1 | ["R1"] | +| 591564 | 347123 | "Command 2" | 2 | ["R2"] | From b866393e9f177f09395e5a6b18d4602711e0195e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 7 May 2025 18:07:01 -0400 Subject: [PATCH 018/153] Add timing to scheduler and command telemetry Start-to-finish execution time is tracked for every command, both per-run (ie mount-to-yield) and total processing time Parent command timing includes child command timing Track overall scheduler `run()` processing time (only per invocation, no aggregation) --- .../org/wpilib/commands3/CommandState.java | 95 +++- .../java/org/wpilib/commands3/Scheduler.java | 76 ++- .../wpilib/commands3/proto/CommandProto.java | 21 +- .../commands3/proto/ProtobufCommand.java | 521 ++++++++++++++++-- .../commands3/proto/ProtobufScheduler.java | 152 ++++- .../org/wpilib/commands3/proto/Scheduler.java | 75 +-- .../commands3/proto/SchedulerProto.java | 2 + commandsv3/src/main/proto/scheduler.proto | 22 + .../org/wpilib/commands3/SchedulerTest.java | 47 +- design-docs/commands-v3.md | 30 +- 10 files changed, 912 insertions(+), 129 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index 6d8a3fea814..392266ac553 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -4,15 +4,86 @@ package org.wpilib.commands3; -/** - * Represents the state of a command as it is executed by the scheduler. - * - * @param command The command being tracked. - * @param parent The parent command composition that scheduled the tracked command. Null if the - * command was scheduled by a top level construct like trigger bindings or manually scheduled by - * a user. For deeply nested compositions, this tracks the direct parent command that - * invoked the schedule() call; in this manner, an ancestry tree can be built, where each {@code - * CommandState} object references a parent node in the tree. - * @param coroutine The coroutine to which the command is bound. - */ -record CommandState(Command command, Command parent, Coroutine coroutine) {} +/** Represents the state of a command as it is executed by the scheduler. */ +final class CommandState { + private final Command command; + private final Command parent; + private final Coroutine coroutine; + private double lastRuntimeMs = -1; + private double totalRuntimeMs = 0; + private final int id = System.identityHashCode(this); + + /** + * @param command The command being tracked. + * @param parent The parent command composition that scheduled the tracked command. Null if the + * command was scheduled by a top level construct like trigger bindings or manually scheduled + * by a user. For deeply nested compositions, this tracks the direct parent command + * that invoked the schedule() call; in this manner, an ancestry tree can be built, where each + * {@code CommandState} object references a parent node in the tree. + * @param coroutine The coroutine to which the command is bound. + */ + CommandState(Command command, Command parent, Coroutine coroutine) { + this.command = command; + this.parent = parent; + this.coroutine = coroutine; + } + + public Command command() { + return command; + } + + public Command parent() { + return parent; + } + + public Coroutine coroutine() { + return coroutine; + } + + /** + * How long the command took to run the last time it executed. Defaults to -1 if the command has + * not run at least once. + * + * @return The runtime, in milliseconds. + */ + public double lastRuntimeMs() { + return lastRuntimeMs; + } + + public void setLastRuntimeMs(double lastRuntimeMs) { + this.lastRuntimeMs = lastRuntimeMs; + totalRuntimeMs += lastRuntimeMs; + } + + public double totalRuntimeMs() { + return totalRuntimeMs; + } + + public int id() { + return id; + } + + @Override + public boolean equals(Object obj) { + return obj instanceof CommandState that && this.id == that.id; + } + + @Override + public int hashCode() { + return id; + } + + @Override + public String toString() { + return "CommandState[" + + "command=" + + command + + ", " + + "parent=" + + parent + + ", " + + "coroutine=" + + coroutine + + ']'; + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 06164fd3968..ac8074cc35b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -4,9 +4,12 @@ package org.wpilib.commands3; +import static edu.wpi.first.units.Units.Microseconds; +import static edu.wpi.first.units.Units.Milliseconds; + import edu.wpi.first.util.protobuf.ProtobufSerializable; +import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.TimedRobot; -import org.wpilib.commands3.proto.SchedulerProto; import edu.wpi.first.wpilibj.event.EventLoop; import java.util.ArrayList; import java.util.Collection; @@ -19,6 +22,7 @@ import java.util.Stack; import java.util.function.Consumer; import java.util.stream.Collectors; +import org.wpilib.commands3.proto.SchedulerProto; /** Manages the lifecycles of {@link Coroutine}-based {@link Command Commands}. */ public class Scheduler implements ProtobufSerializable { @@ -46,7 +50,9 @@ public class Scheduler implements ProtobufSerializable { /** The scope for continuations to yield to. */ private final ContinuationScope scope = new ContinuationScope("coroutine commands"); + // Telemetry public static final SchedulerProto proto = new SchedulerProto(); + private double lastRunTimeMs = -1; /** The default scheduler instance. */ private static final Scheduler defaultScheduler = new Scheduler(); @@ -347,6 +353,8 @@ public void cancel(Command command) { * TimedRobot#robotPeriodic()} */ public void run() { + long startMicros = RobotController.getTime(); + // Process triggers first; these tend to queue and cancel commands eventLoop.poll(); @@ -354,6 +362,9 @@ public void run() { promoteScheduledCommands(); runCommands(); scheduleDefaultCommands(); + + long endMicros = RobotController.getTime(); + lastRunTimeMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); } private void promoteScheduledCommands() { @@ -405,11 +416,16 @@ private void runCommand(CommandState state) { var previousState = currentState(); + executingCommands.push(state); + long startMicros = RobotController.getTime(); coroutine.mount(); try { - executingCommands.push(state); coroutine.runToYieldPoint(); } finally { + long endMicros = RobotController.getTime(); + double elapsedMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); + state.setLastRuntimeMs(elapsedMs); + if (currentState() == state) { // Remove the command we just ran from the top of the stack executingCommands.pop(); @@ -584,4 +600,60 @@ public Command getParentOf(Command command) { } return state.parent(); } + + /** + * Gets how long a command took to run in the previous cycle. If the command is not currently + * running, returns -1. + * + * @param command The command to check + * @return How long, in milliseconds, the command last took to execute. + */ + public double lastRuntimeMs(Command command) { + if (commandStates.containsKey(command)) { + return commandStates.get(command).lastRuntimeMs(); + } else { + return -1; + } + } + + /** + * Gets how long a command has taken to run, in aggregate, since it was most recently scheduled. + * If the command is not currently running, returns -1. + * + * @param command The command to check + * @return How long, in milliseconds, the command has taken to execute in total + */ + public double totalRuntimeMs(Command command) { + if (commandStates.containsKey(command)) { + return commandStates.get(command).totalRuntimeMs(); + } else { + // Not running; no data + return -1; + } + } + + public int runId(Command command) { + if (commandStates.containsKey(command)) { + return commandStates.get(command).id(); + } + + // Check scheduled commands + for (var scheduled : onDeck) { + if (scheduled.command() == command) { + return scheduled.id(); + } + } + + return 0; + } + + /** + * Gets how long the scheduler took to process its most recent {@link #run()} invocation, in + * milliseconds. Defaults to -1 if the scheduler has not yet run. + * + * @return How long, in milliseconds, the scheduler last took to execute. + */ + public double lastRuntimeMs() { + return lastRunTimeMs; + } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index 281e81a7381..4b6f51c1f93 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -9,6 +9,7 @@ import org.wpilib.commands3.Scheduler; import us.hebi.quickbuf.Descriptors; +/** Protobuf serde for running commands. */ public class CommandProto implements Protobuf { private final Scheduler scheduler; @@ -38,20 +39,24 @@ public Command unpack(ProtobufCommand msg) { } @Override - public void pack(ProtobufCommand msg, Command value) { - // Use identityHashCode for ID fields. Object hashCode can be overridden and collide - msg.setId(System.identityHashCode(value)); - if (scheduler.getParentOf(value) instanceof Command parent) { - msg.setParentId(System.identityHashCode(parent)); + public void pack(ProtobufCommand msg, Command command) { + msg.setId(scheduler.runId(command)); + if (scheduler.getParentOf(command) instanceof Command parent) { + msg.setParentId(scheduler.runId(parent)); } - msg.setName(value.name()); - msg.setPriority(value.priority()); + msg.setName(command.name()); + msg.setPriority(command.priority()); - for (var requirement : value.requirements()) { + for (var requirement : command.requirements()) { var rrp = new RequireableResourceProto(); ProtobufRequireableResource requirementMessage = rrp.createMessage(); rrp.pack(requirementMessage, requirement); msg.addRequirements(requirementMessage); } + + if (scheduler.isRunning(command)) { + msg.setLastTimeMs(scheduler.lastRuntimeMs(command)); + msg.setTotalTimeMs(scheduler.totalRuntimeMs(command)); + } } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java index 3191d1d44f3..470720ae428 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java @@ -15,6 +15,7 @@ import us.hebi.quickbuf.ProtoMessage; import us.hebi.quickbuf.ProtoSink; import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; import us.hebi.quickbuf.RepeatedMessage; import us.hebi.quickbuf.Utf8String; @@ -23,19 +24,85 @@ public final class ProtobufCommand extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; - /** optional int32 priority = 4; */ + /** + * + * + *

+   *  How much time the command took to execute in its most recent run.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double last_time_ms = 6; + */ + private double lastTimeMs; + + /** + * + * + *
+   *  How long the command has taken to run, in aggregate.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double total_time_ms = 7; + */ + private double totalTimeMs; + + /** + * + * + *
+   *  The priority level of the command.
+   * 
+ * + * optional int32 priority = 4; + */ private int priority; - /** optional uint32 id = 1; */ + /** + * + * + *
+   *  A unique ID for the command.
+   *  Different invocations of the same command object have different IDs.
+   * 
+ * + * optional uint32 id = 1; + */ private int id; - /** optional uint32 parent_id = 2; */ + /** + * + * + *
+   *  The ID of the parent command.
+   *  Not included in the message for top-level commands.
+   * 
+ * + * optional uint32 parent_id = 2; + */ private int parentId; - /** optional string name = 3; */ + /** + * + * + *
+   *  The name of the command.
+   * 
+ * + * optional string name = 3; + */ private final Utf8String name = Utf8String.newEmptyInstance(); - /** repeated .wpi.proto.ProtobufRequireableResource requirements = 5; */ + /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + */ private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufRequireableResource.getFactory()); @@ -49,26 +116,182 @@ public static ProtobufCommand newInstance() { } /** + * + * + *
+   *  How much time the command took to execute in its most recent run.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double last_time_ms = 6; + * + * @return whether the lastTimeMs field is set + */ + public boolean hasLastTimeMs() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * + * + *
+   *  How much time the command took to execute in its most recent run.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double last_time_ms = 6; + * + * @return this + */ + public ProtobufCommand clearLastTimeMs() { + bitField0_ &= ~0x00000002; + lastTimeMs = 0D; + return this; + } + + /** + * + * + *
+   *  How much time the command took to execute in its most recent run.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double last_time_ms = 6; + * + * @return the lastTimeMs + */ + public double getLastTimeMs() { + return lastTimeMs; + } + + /** + * + * + *
+   *  How much time the command took to execute in its most recent run.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double last_time_ms = 6; + * + * @param value the lastTimeMs to set + * @return this + */ + public ProtobufCommand setLastTimeMs(final double value) { + bitField0_ |= 0x00000002; + lastTimeMs = value; + return this; + } + + /** + * + * + *
+   *  How long the command has taken to run, in aggregate.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double total_time_ms = 7; + * + * @return whether the totalTimeMs field is set + */ + public boolean hasTotalTimeMs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * + * + *
+   *  How long the command has taken to run, in aggregate.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double total_time_ms = 7; + * + * @return this + */ + public ProtobufCommand clearTotalTimeMs() { + bitField0_ &= ~0x00000001; + totalTimeMs = 0D; + return this; + } + + /** + * + * + *
+   *  How long the command has taken to run, in aggregate.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double total_time_ms = 7; + * + * @return the totalTimeMs + */ + public double getTotalTimeMs() { + return totalTimeMs; + } + + /** + * + * + *
+   *  How long the command has taken to run, in aggregate.
+   *  Only included in a message for an actively running command.
+   * 
+ * + * optional double total_time_ms = 7; + * + * @param value the totalTimeMs to set + * @return this + */ + public ProtobufCommand setTotalTimeMs(final double value) { + bitField0_ |= 0x00000001; + totalTimeMs = value; + return this; + } + + /** + * + * + *
+   *  The priority level of the command.
+   * 
+ * * optional int32 priority = 4; * * @return whether the priority field is set */ public boolean hasPriority() { - return (bitField0_ & 0x00000001) != 0; + return (bitField0_ & 0x00000008) != 0; } /** + * + * + *
+   *  The priority level of the command.
+   * 
+ * * optional int32 priority = 4; * * @return this */ public ProtobufCommand clearPriority() { - bitField0_ &= ~0x00000001; + bitField0_ &= ~0x00000008; priority = 0; return this; } /** + * + * + *
+   *  The priority level of the command.
+   * 
+ * * optional int32 priority = 4; * * @return the priority @@ -78,38 +301,65 @@ public int getPriority() { } /** + * + * + *
+   *  The priority level of the command.
+   * 
+ * * optional int32 priority = 4; * * @param value the priority to set * @return this */ public ProtobufCommand setPriority(final int value) { - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000008; priority = value; return this; } /** + * + * + *
+   *  A unique ID for the command.
+   *  Different invocations of the same command object have different IDs.
+   * 
+ * * optional uint32 id = 1; * * @return whether the id field is set */ public boolean hasId() { - return (bitField0_ & 0x00000002) != 0; + return (bitField0_ & 0x00000010) != 0; } /** + * + * + *
+   *  A unique ID for the command.
+   *  Different invocations of the same command object have different IDs.
+   * 
+ * * optional uint32 id = 1; * * @return this */ public ProtobufCommand clearId() { - bitField0_ &= ~0x00000002; + bitField0_ &= ~0x00000010; id = 0; return this; } /** + * + * + *
+   *  A unique ID for the command.
+   *  Different invocations of the same command object have different IDs.
+   * 
+ * * optional uint32 id = 1; * * @return the id @@ -119,18 +369,32 @@ public int getId() { } /** + * + * + *
+   *  A unique ID for the command.
+   *  Different invocations of the same command object have different IDs.
+   * 
+ * * optional uint32 id = 1; * * @param value the id to set * @return this */ public ProtobufCommand setId(final int value) { - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000010; id = value; return this; } /** + * + * + *
+   *  The ID of the parent command.
+   *  Not included in the message for top-level commands.
+   * 
+ * * optional uint32 parent_id = 2; * * @return whether the parentId field is set @@ -140,6 +404,13 @@ public boolean hasParentId() { } /** + * + * + *
+   *  The ID of the parent command.
+   *  Not included in the message for top-level commands.
+   * 
+ * * optional uint32 parent_id = 2; * * @return this @@ -151,6 +422,13 @@ public ProtobufCommand clearParentId() { } /** + * + * + *
+   *  The ID of the parent command.
+   *  Not included in the message for top-level commands.
+   * 
+ * * optional uint32 parent_id = 2; * * @return the parentId @@ -160,6 +438,13 @@ public int getParentId() { } /** + * + * + *
+   *  The ID of the parent command.
+   *  Not included in the message for top-level commands.
+   * 
+ * * optional uint32 parent_id = 2; * * @param value the parentId to set @@ -172,26 +457,44 @@ public ProtobufCommand setParentId(final int value) { } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @return whether the name field is set */ public boolean hasName() { - return (bitField0_ & 0x00000008) != 0; + return (bitField0_ & 0x00000020) != 0; } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @return this */ public ProtobufCommand clearName() { - bitField0_ &= ~0x00000008; + bitField0_ &= ~0x00000020; name.clear(); return this; } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @return the name @@ -201,6 +504,12 @@ public String getName() { } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @return internal {@code Utf8String} representation of name for reading @@ -210,60 +519,96 @@ public Utf8String getNameBytes() { } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @return internal {@code Utf8String} representation of name for modifications */ public Utf8String getMutableNameBytes() { - bitField0_ |= 0x00000008; + bitField0_ |= 0x00000020; return this.name; } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @param value the name to set * @return this */ public ProtobufCommand setName(final CharSequence value) { - bitField0_ |= 0x00000008; + bitField0_ |= 0x00000020; name.copyFrom(value); return this; } /** + * + * + *
+   *  The name of the command.
+   * 
+ * * optional string name = 3; * * @param value the name to set * @return this */ public ProtobufCommand setName(final Utf8String value) { - bitField0_ |= 0x00000008; + bitField0_ |= 0x00000020; name.copyFrom(value); return this; } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; * * @return whether the requirements field is set */ public boolean hasRequirements() { - return (bitField0_ & 0x00000010) != 0; + return (bitField0_ & 0x00000040) != 0; } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; * * @return this */ public ProtobufCommand clearRequirements() { - bitField0_ &= ~0x00000010; + bitField0_ &= ~0x00000040; requirements.clear(); return this; } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method * returns the internal storage object without modifying any has state. The returned object should * not be modified and be treated as read-only. @@ -277,6 +622,12 @@ public RepeatedMessage getRequirements() { } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method * returns the internal storage object and sets the corresponding has state. The returned object * will become part of this message and its contents may be modified as long as the has state is @@ -285,30 +636,42 @@ public RepeatedMessage getRequirements() { * @return internal storage object for modifications */ public RepeatedMessage getMutableRequirements() { - bitField0_ |= 0x00000010; + bitField0_ |= 0x00000040; return requirements; } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; * * @param value the requirements to add * @return this */ public ProtobufCommand addRequirements(final ProtobufRequireableResource value) { - bitField0_ |= 0x00000010; + bitField0_ |= 0x00000040; requirements.add(value); return this; } /** + * + * + *
+   *  The resources required by the command.
+   * 
+ * * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; * * @param values the requirements to add * @return this */ public ProtobufCommand addAllRequirements(final ProtobufRequireableResource... values) { - bitField0_ |= 0x00000010; + bitField0_ |= 0x00000040; requirements.addAll(values); return this; } @@ -318,6 +681,8 @@ public ProtobufCommand copyFrom(final ProtobufCommand other) { cachedSize = other.cachedSize; if ((bitField0_ | other.bitField0_) != 0) { bitField0_ = other.bitField0_; + lastTimeMs = other.lastTimeMs; + totalTimeMs = other.totalTimeMs; priority = other.priority; id = other.id; parentId = other.parentId; @@ -333,6 +698,12 @@ public ProtobufCommand mergeFrom(final ProtobufCommand other) { return this; } cachedSize = -1; + if (other.hasLastTimeMs()) { + setLastTimeMs(other.lastTimeMs); + } + if (other.hasTotalTimeMs()) { + setTotalTimeMs(other.totalTimeMs); + } if (other.hasPriority()) { setPriority(other.priority); } @@ -358,6 +729,8 @@ public ProtobufCommand clear() { } cachedSize = -1; bitField0_ = 0; + lastTimeMs = 0D; + totalTimeMs = 0D; priority = 0; id = 0; parentId = 0; @@ -388,6 +761,8 @@ public boolean equals(Object o) { } ProtobufCommand other = (ProtobufCommand) o; return bitField0_ == other.bitField0_ + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) + && (!hasTotalTimeMs() || ProtoUtil.isEqual(totalTimeMs, other.totalTimeMs)) && (!hasPriority() || priority == other.priority) && (!hasId() || id == other.id) && (!hasParentId() || parentId == other.parentId) @@ -397,11 +772,19 @@ public boolean equals(Object o) { @Override public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 49); + output.writeDoubleNoTag(lastTimeMs); + } if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 57); + output.writeDoubleNoTag(totalTimeMs); + } + if ((bitField0_ & 0x00000008) != 0) { output.writeRawByte((byte) 32); output.writeInt32NoTag(priority); } - if ((bitField0_ & 0x00000002) != 0) { + if ((bitField0_ & 0x00000010) != 0) { output.writeRawByte((byte) 8); output.writeUInt32NoTag(id); } @@ -409,11 +792,11 @@ public void writeTo(final ProtoSink output) throws IOException { output.writeRawByte((byte) 16); output.writeUInt32NoTag(parentId); } - if ((bitField0_ & 0x00000008) != 0) { + if ((bitField0_ & 0x00000020) != 0) { output.writeRawByte((byte) 26); output.writeStringNoTag(name); } - if ((bitField0_ & 0x00000010) != 0) { + if ((bitField0_ & 0x00000040) != 0) { for (int i = 0; i < requirements.length(); i++) { output.writeRawByte((byte) 42); output.writeMessageNoTag(requirements.get(i)); @@ -424,19 +807,25 @@ public void writeTo(final ProtoSink output) throws IOException { @Override protected int computeSerializedSize() { int size = 0; + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { size += 1 + ProtoSink.computeInt32SizeNoTag(priority); } - if ((bitField0_ & 0x00000002) != 0) { + if ((bitField0_ & 0x00000010) != 0) { size += 1 + ProtoSink.computeUInt32SizeNoTag(id); } if ((bitField0_ & 0x00000004) != 0) { size += 1 + ProtoSink.computeUInt32SizeNoTag(parentId); } - if ((bitField0_ & 0x00000008) != 0) { + if ((bitField0_ & 0x00000020) != 0) { size += 1 + ProtoSink.computeStringSizeNoTag(name); } - if ((bitField0_ & 0x00000010) != 0) { + if ((bitField0_ & 0x00000040) != 0) { size += (1 * requirements.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(requirements); } return size; @@ -449,11 +838,31 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { int tag = input.readTag(); while (true) { switch (tag) { + case 49: + { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 57) { + break; + } + } + case 57: + { + // totalTimeMs + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 32) { + break; + } + } case 32: { // priority priority = input.readInt32(); - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000008; tag = input.readTag(); if (tag != 8) { break; @@ -463,7 +872,7 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { { // id id = input.readUInt32(); - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000010; tag = input.readTag(); if (tag != 16) { break; @@ -483,7 +892,7 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { { // name input.readString(name); - bitField0_ |= 0x00000008; + bitField0_ |= 0x00000020; tag = input.readTag(); if (tag != 42) { break; @@ -493,7 +902,7 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { { // requirements tag = input.readRepeatedMessage(requirements, tag); - bitField0_ |= 0x00000010; + bitField0_ |= 0x00000040; if (tag != 0) { break; } @@ -517,19 +926,25 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { @Override public void writeTo(final JsonSink output) throws IOException { output.beginObject(); + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); + } if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.totalTimeMs, totalTimeMs); + } + if ((bitField0_ & 0x00000008) != 0) { output.writeInt32(FieldNames.priority, priority); } - if ((bitField0_ & 0x00000002) != 0) { + if ((bitField0_ & 0x00000010) != 0) { output.writeUInt32(FieldNames.id, id); } if ((bitField0_ & 0x00000004) != 0) { output.writeUInt32(FieldNames.parentId, parentId); } - if ((bitField0_ & 0x00000008) != 0) { + if ((bitField0_ & 0x00000020) != 0) { output.writeString(FieldNames.name, name); } - if ((bitField0_ & 0x00000010) != 0) { + if ((bitField0_ & 0x00000040) != 0) { output.writeRepeatedMessage(FieldNames.requirements, requirements); } output.endObject(); @@ -542,12 +957,38 @@ public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { } while (!input.isAtEnd()) { switch (input.readFieldHash()) { + case 1958056841: + case -740797521: + { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -717217353: + case 1006112349: + { + if (input.isAtField(FieldNames.totalTimeMs)) { + if (!input.trySkipNullValue()) { + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } case -1165461084: { if (input.isAtField(FieldNames.priority)) { if (!input.trySkipNullValue()) { priority = input.readInt32(); - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000008; } } else { input.skipUnknownField(); @@ -559,7 +1000,7 @@ public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { if (input.isAtField(FieldNames.id)) { if (!input.trySkipNullValue()) { id = input.readUInt32(); - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000010; } } else { input.skipUnknownField(); @@ -584,7 +1025,7 @@ public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { if (input.isAtField(FieldNames.name)) { if (!input.trySkipNullValue()) { input.readString(name); - bitField0_ |= 0x00000008; + bitField0_ |= 0x00000020; } } else { input.skipUnknownField(); @@ -596,7 +1037,7 @@ public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { if (input.isAtField(FieldNames.requirements)) { if (!input.trySkipNullValue()) { input.readRepeatedMessage(requirements); - bitField0_ |= 0x00000010; + bitField0_ |= 0x00000040; } } else { input.skipUnknownField(); @@ -661,6 +1102,10 @@ public ProtobufCommand create() { /** Contains name constants used for serializing JSON */ static class FieldNames { + static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); + + static final FieldName totalTimeMs = FieldName.forField("totalTimeMs", "total_time_ms"); + static final FieldName priority = FieldName.forField("priority"); static final FieldName id = FieldName.forField("id"); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java index d8a95813c40..5d20a3416b5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java @@ -15,6 +15,7 @@ import us.hebi.quickbuf.ProtoMessage; import us.hebi.quickbuf.ProtoSink; import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; import us.hebi.quickbuf.RepeatedMessage; /** Protobuf type {@code ProtobufScheduler} */ @@ -22,6 +23,17 @@ public final class ProtobufScheduler extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; + /** + * + * + *
+   *  How much time the scheduler took in its last `run()` invocation.
+   * 
+ * + * optional double last_time_ms = 3; + */ + private double lastTimeMs; + /** * * @@ -49,6 +61,71 @@ public static ProtobufScheduler newInstance() { return new ProtobufScheduler(); } + /** + * + * + *
+   *  How much time the scheduler took in its last `run()` invocation.
+   * 
+ * + * optional double last_time_ms = 3; + * + * @return whether the lastTimeMs field is set + */ + public boolean hasLastTimeMs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * + * + *
+   *  How much time the scheduler took in its last `run()` invocation.
+   * 
+ * + * optional double last_time_ms = 3; + * + * @return this + */ + public ProtobufScheduler clearLastTimeMs() { + bitField0_ &= ~0x00000001; + lastTimeMs = 0D; + return this; + } + + /** + * + * + *
+   *  How much time the scheduler took in its last `run()` invocation.
+   * 
+ * + * optional double last_time_ms = 3; + * + * @return the lastTimeMs + */ + public double getLastTimeMs() { + return lastTimeMs; + } + + /** + * + * + *
+   *  How much time the scheduler took in its last `run()` invocation.
+   * 
+ * + * optional double last_time_ms = 3; + * + * @param value the lastTimeMs to set + * @return this + */ + public ProtobufScheduler setLastTimeMs(final double value) { + bitField0_ |= 0x00000001; + lastTimeMs = value; + return this; + } + /** * * @@ -63,7 +140,7 @@ public static ProtobufScheduler newInstance() { * @return whether the queuedCommands field is set */ public boolean hasQueuedCommands() { - return (bitField0_ & 0x00000001) != 0; + return (bitField0_ & 0x00000002) != 0; } /** @@ -80,7 +157,7 @@ public boolean hasQueuedCommands() { * @return this */ public ProtobufScheduler clearQueuedCommands() { - bitField0_ &= ~0x00000001; + bitField0_ &= ~0x00000002; queuedCommands.clear(); return this; } @@ -122,7 +199,7 @@ public RepeatedMessage getQueuedCommands() { * @return internal storage object for modifications */ public RepeatedMessage getMutableQueuedCommands() { - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000002; return queuedCommands; } @@ -141,7 +218,7 @@ public RepeatedMessage getMutableQueuedCommands() { * @return this */ public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000002; queuedCommands.add(value); return this; } @@ -161,7 +238,7 @@ public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { * @return this */ public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000002; queuedCommands.addAll(values); return this; } @@ -172,7 +249,7 @@ public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { * @return whether the runningCommands field is set */ public boolean hasRunningCommands() { - return (bitField0_ & 0x00000002) != 0; + return (bitField0_ & 0x00000004) != 0; } /** @@ -181,7 +258,7 @@ public boolean hasRunningCommands() { * @return this */ public ProtobufScheduler clearRunningCommands() { - bitField0_ &= ~0x00000002; + bitField0_ &= ~0x00000004; runningCommands.clear(); return this; } @@ -207,7 +284,7 @@ public RepeatedMessage getRunningCommands() { * @return internal storage object for modifications */ public RepeatedMessage getMutableRunningCommands() { - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000004; return runningCommands; } @@ -218,7 +295,7 @@ public RepeatedMessage getMutableRunningCommands() { * @return this */ public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000004; runningCommands.add(value); return this; } @@ -230,7 +307,7 @@ public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { * @return this */ public ProtobufScheduler addAllRunningCommands(final ProtobufCommand... values) { - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000004; runningCommands.addAll(values); return this; } @@ -240,6 +317,7 @@ public ProtobufScheduler copyFrom(final ProtobufScheduler other) { cachedSize = other.cachedSize; if ((bitField0_ | other.bitField0_) != 0) { bitField0_ = other.bitField0_; + lastTimeMs = other.lastTimeMs; queuedCommands.copyFrom(other.queuedCommands); runningCommands.copyFrom(other.runningCommands); } @@ -252,6 +330,9 @@ public ProtobufScheduler mergeFrom(final ProtobufScheduler other) { return this; } cachedSize = -1; + if (other.hasLastTimeMs()) { + setLastTimeMs(other.lastTimeMs); + } if (other.hasQueuedCommands()) { getMutableQueuedCommands().addAll(other.queuedCommands); } @@ -268,6 +349,7 @@ public ProtobufScheduler clear() { } cachedSize = -1; bitField0_ = 0; + lastTimeMs = 0D; queuedCommands.clear(); runningCommands.clear(); return this; @@ -295,6 +377,7 @@ public boolean equals(Object o) { } ProtobufScheduler other = (ProtobufScheduler) o; return bitField0_ == other.bitField0_ + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); } @@ -302,12 +385,16 @@ public boolean equals(Object o) { @Override public void writeTo(final ProtoSink output) throws IOException { if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(lastTimeMs); + } + if ((bitField0_ & 0x00000002) != 0) { for (int i = 0; i < queuedCommands.length(); i++) { output.writeRawByte((byte) 10); output.writeMessageNoTag(queuedCommands.get(i)); } } - if ((bitField0_ & 0x00000002) != 0) { + if ((bitField0_ & 0x00000004) != 0) { for (int i = 0; i < runningCommands.length(); i++) { output.writeRawByte((byte) 18); output.writeMessageNoTag(runningCommands.get(i)); @@ -319,10 +406,13 @@ public void writeTo(final ProtoSink output) throws IOException { protected int computeSerializedSize() { int size = 0; if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { size += (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); } - if ((bitField0_ & 0x00000002) != 0) { + if ((bitField0_ & 0x00000004) != 0) { size += (1 * runningCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); @@ -337,11 +427,21 @@ public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { int tag = input.readTag(); while (true) { switch (tag) { + case 25: + { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 10) { + break; + } + } case 10: { // queuedCommands tag = input.readRepeatedMessage(queuedCommands, tag); - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000002; if (tag != 18) { break; } @@ -350,7 +450,7 @@ public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { { // runningCommands tag = input.readRepeatedMessage(runningCommands, tag); - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000004; if (tag != 0) { break; } @@ -375,9 +475,12 @@ public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { public void writeTo(final JsonSink output) throws IOException { output.beginObject(); if ((bitField0_ & 0x00000001) != 0) { - output.writeRepeatedMessage(FieldNames.queuedCommands, queuedCommands); + output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); } if ((bitField0_ & 0x00000002) != 0) { + output.writeRepeatedMessage(FieldNames.queuedCommands, queuedCommands); + } + if ((bitField0_ & 0x00000004) != 0) { output.writeRepeatedMessage(FieldNames.runningCommands, runningCommands); } output.endObject(); @@ -390,13 +493,26 @@ public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { } while (!input.isAtEnd()) { switch (input.readFieldHash()) { + case 1958056841: + case -740797521: + { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } case -167160549: case -1904270380: { if (input.isAtField(FieldNames.queuedCommands)) { if (!input.trySkipNullValue()) { input.readRepeatedMessage(queuedCommands); - bitField0_ |= 0x00000001; + bitField0_ |= 0x00000002; } } else { input.skipUnknownField(); @@ -409,7 +525,7 @@ public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { if (input.isAtField(FieldNames.runningCommands)) { if (!input.trySkipNullValue()) { input.readRepeatedMessage(runningCommands); - bitField0_ |= 0x00000002; + bitField0_ |= 0x00000004; } } else { input.skipUnknownField(); @@ -475,6 +591,8 @@ public ProtobufScheduler create() { /** Contains name constants used for serializing JSON */ static class FieldNames { + static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); + static final FieldName queuedCommands = FieldName.forField("queuedCommands", "queued_commands"); static final FieldName runningCommands = diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java index d21fa770c95..9a5abd7bc82 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java @@ -12,36 +12,49 @@ public final class Scheduler { private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64( - 1691, + 2511, "Ciljb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5wcm90bxIJd3BpLnByb3RvIjEKG1By" - + "b3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZRISCgRuYW1lGAEgASgJUgRuYW1lIroBCg9Qcm90b2J1ZkNv" - + "bW1hbmQSDgoCaWQYASABKA1SAmlkEhsKCXBhcmVudF9pZBgCIAEoDVIIcGFyZW50SWQSEgoEbmFtZRgD" - + "IAEoCVIEbmFtZRIaCghwcmlvcml0eRgEIAEoBVIIcHJpb3JpdHkSSgoMcmVxdWlyZW1lbnRzGAUgAygL" - + "MiYud3BpLnByb3RvLlByb3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZVIMcmVxdWlyZW1lbnRzIp8BChFQ" - + "cm90b2J1ZlNjaGVkdWxlchJDCg9xdWV1ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9i" - + "dWZDb21tYW5kUg5xdWV1ZWRDb21tYW5kcxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnBy" - + "b3RvLlByb3RvYnVmQ29tbWFuZFIPcnVubmluZ0NvbW1hbmRzQioKJmVkdS53cGkuZmlyc3Qud3BpbGli" - + "ai5jb21tYW5kc3YzLnByb3RvUAFKnAkKBhIEAAAiAQoICgEMEgMAABIKCAoBAhIDAgASCggKAQgSAwQA" - + "PwoJCgIIARIDBAA/CggKAQgSAwUAIgoJCgIIChIDBQAiCrICCgIEABIEEAASATKlAgogTk9URTogYWxs" - + "b2NhdGlvbj1sYXp5bXNnIGlzIHJlcXVpcmVkIHdoZW4gZ2VuZXJhdGluZyB0aGUgSmF2YSBjbGFzc2Vz" - + "IGZvciB0aGlzIGZpbGUsCiAgICAgICBkdWUgdG8gdGhlIHJlY3Vyc2l2ZSBQcm90b2J1ZkNvbW1hbmQg" - + "c2NoZW1hCgphbGx3cGlsaWIgJCBwcm90b2MtcXVpY2tidWYgXAotLXF1aWNrYnVmX291dD1hbGxvY2F0" - + "aW9uPWxhenltc2csZ2VuX2Rlc2NyaXB0b3JzPXRydWU6Y29tbWFuZHN2My9zcmMvbWFpbi9qYXZhIFwK" - + "Y29tbWFuZHN2My9zcmMvbWFpbi9wcm90by9zY2hlZHVsZXIucHJvdG8KCgoKAwQAARIDEAgjCgsKBAQA" - + "AgASAxECEgoMCgUEAAIABRIDEQIICgwKBQQAAgABEgMRCQ0KDAoFBAACAAMSAxEQEQoKCgIEARIEFAAa" - + "AQoKCgMEAQESAxQIFwoLCgQEAQIAEgMVAhAKDAoFBAECAAUSAxUCCAoMCgUEAQIAARIDFQkLCgwKBQQB" - + "AgADEgMVDg8KCwoEBAECARIDFgIXCgwKBQQBAgEFEgMWAggKDAoFBAECAQESAxYJEgoMCgUEAQIBAxID" - + "FhUWCgsKBAQBAgISAxcCEgoMCgUEAQICBRIDFwIICgwKBQQBAgIBEgMXCQ0KDAoFBAECAgMSAxcQEQoL" - + "CgQEAQIDEgMYAhUKDAoFBAECAwUSAxgCBwoMCgUEAQIDARIDGAgQCgwKBQQBAgMDEgMYExQKCwoEBAEC", - "BBIDGQI4CgwKBQQBAgQEEgMZAgoKDAoFBAECBAYSAxkLJgoMCgUEAQIEARIDGSczCgwKBQQBAgQDEgMZ" - + "NjcKCgoCBAISBBwAIgEKCgoDBAIBEgMcCBkKjQIKBAQCAgASAyACLxr/ASBOb3RlOiBjb21tYW5kcyBh" - + "cmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2ggb2NjdXJzIGltbWVkaWF0ZWx5IGJl" - + "Zm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5pbmcuIEVudHJpZXMgd2lsbCBvbmx5" - + "IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVsZXIKIF9hZnRlcl8gbWFudWFsbHkg" - + "c2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxpbmcgc2NoZWR1bGVyLnJ1bigpCgoM" - + "CgUEAgIABBIDIAIKCgwKBQQCAgAGEgMgCxoKDAoFBAICAAESAyAbKgoMCgUEAgIAAxIDIC0uCgsKBAQC" - + "AgESAyECMAoMCgUEAgIBBBIDIQIKCgwKBQQCAgEGEgMhCxoKDAoFBAICAQESAyEbKwoMCgUEAgIBAxID" - + "IS4vYgZwcm90bzM="); + + "b3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZRISCgRuYW1lGAEgASgJUgRuYW1lIsACCg9Qcm90b2J1ZkNv" + + "bW1hbmQSDgoCaWQYASABKA1SAmlkEiAKCXBhcmVudF9pZBgCIAEoDUgAUghwYXJlbnRJZIgBARISCgRu" + + "YW1lGAMgASgJUgRuYW1lEhoKCHByaW9yaXR5GAQgASgFUghwcmlvcml0eRJKCgxyZXF1aXJlbWVudHMY" + + "BSADKAsyJi53cGkucHJvdG8uUHJvdG9idWZSZXF1aXJlYWJsZVJlc291cmNlUgxyZXF1aXJlbWVudHMS" + + "JQoMbGFzdF90aW1lX21zGAYgASgBSAFSCmxhc3RUaW1lTXOIAQESJwoNdG90YWxfdGltZV9tcxgHIAEo" + + "AUgCUgt0b3RhbFRpbWVNc4gBAUIMCgpfcGFyZW50X2lkQg8KDV9sYXN0X3RpbWVfbXNCEAoOX3RvdGFs" + + "X3RpbWVfbXMiwQEKEVByb3RvYnVmU2NoZWR1bGVyEkMKD3F1ZXVlZF9jb21tYW5kcxgBIAMoCzIaLndw" + + "aS5wcm90by5Qcm90b2J1ZkNvbW1hbmRSDnF1ZXVlZENvbW1hbmRzEkUKEHJ1bm5pbmdfY29tbWFuZHMY" + + "AiADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg9ydW5uaW5nQ29tbWFuZHMSIAoMbGFzdF90" + + "aW1lX21zGAMgASgBUgpsYXN0VGltZU1zQh4KGm9yZy53cGlsaWIuY29tbWFuZHMzLnByb3RvUAFKtA4K" + + "BhIEAAA1AQoICgEMEgMAABIKCAoBAhIDAgASCggKAQgSAwQAMwoJCgIIARIDBAAzCggKAQgSAwUAIgoJ" + + "CgIIChIDBQAiCpUBCgIEABIEDQAPATKIAQphbGx3cGlsaWIgJCBwcm90b2MtcXVpY2tidWYgXAotLXF1" + + "aWNrYnVmX291dD1nZW5fZGVzY3JpcHRvcnM9dHJ1ZTpjb21tYW5kc3YzL3NyYy9tYWluL2phdmEgXApj" + + "b21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5wcm90bwoKCgoDBAABEgMNCCMKCwoEBAAC" + + "ABIDDgISCgwKBQQAAgAFEgMOAggKDAoFBAACAAESAw4JDQoMCgUEAAIAAxIDDhARCgoKAgQBEgQRACoB" + + "CgoKAwQBARIDEQgXCnEKBAQBAgASAxQCEBpkIEEgdW5pcXVlIElEIGZvciB0aGUgY29tbWFuZC4KIERp" + + "ZmZlcmVudCBpbnZvY2F0aW9ucyBvZiB0aGUgc2FtZSBjb21tYW5kIG9iamVjdCBoYXZlIGRpZmZlcmVu" + + "dCBJRHMuCgoMCgUEAQIABRIDFAIICgwKBQQBAgABEgMUCQsKDAoFBAECAAMSAxQODwphCgQEAQIBEgMY" + + "AiAaVCBUaGUgSUQgb2YgdGhlIHBhcmVudCBjb21tYW5kLgogTm90IGluY2x1ZGVkIGluIHRoZSBtZXNz", + "YWdlIGZvciB0b3AtbGV2ZWwgY29tbWFuZHMuCgoMCgUEAQIBBBIDGAIKCgwKBQQBAgEFEgMYCxEKDAoF" + + "BAECAQESAxgSGwoMCgUEAQIBAxIDGB4fCicKBAQBAgISAxsCEhoaIFRoZSBuYW1lIG9mIHRoZSBjb21t" + + "YW5kLgoKDAoFBAECAgUSAxsCCAoMCgUEAQICARIDGwkNCgwKBQQBAgIDEgMbEBEKMQoEBAECAxIDHgIV" + + "GiQgVGhlIHByaW9yaXR5IGxldmVsIG9mIHRoZSBjb21tYW5kLgoKDAoFBAECAwUSAx4CBwoMCgUEAQID" + + "ARIDHggQCgwKBQQBAgMDEgMeExQKNQoEBAECBBIDIQI4GiggVGhlIHJlc291cmNlcyByZXF1aXJlZCBi" + + "eSB0aGUgY29tbWFuZC4KCgwKBQQBAgQEEgMhAgoKDAoFBAECBAYSAyELJgoMCgUEAQIEARIDISczCgwK" + + "BQQBAgQDEgMhNjcKjgEKBAQBAgUSAyUCIxqAASBIb3cgbXVjaCB0aW1lIHRoZSBjb21tYW5kIHRvb2sg" + + "dG8gZXhlY3V0ZSBpbiBpdHMgbW9zdCByZWNlbnQgcnVuLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3Nh" + + "Z2UgZm9yIGFuIGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgUEEgMlAgoKDAoFBAECBQUS" + + "AyULEQoMCgUEAQIFARIDJRIeCgwKBQQBAgUDEgMlISIKgAEKBAQBAgYSAykCJBpzIEhvdyBsb25nIHRo" + + "ZSBjb21tYW5kIGhhcyB0YWtlbiB0byBydW4sIGluIGFnZ3JlZ2F0ZS4KIE9ubHkgaW5jbHVkZWQgaW4g" + + "YSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQuCgoMCgUEAQIGBBIDKQIKCgwK" + + "BQQBAgYFEgMpCxEKDAoFBAECBgESAykSHwoMCgUEAQIGAxIDKSIjCgoKAgQCEgQsADUBCgoKAwQCARID" + + "LAgZCo0CCgQEAgIAEgMwAi8a/wEgTm90ZTogY29tbWFuZHMgYXJlIGdlbmVyYWxseSBxdWV1ZWQgYnkg" + + "dHJpZ2dlcnMsIHdoaWNoIG9jY3VycyBpbW1lZGlhdGVseSBiZWZvcmUgdGhleSBhcmUKIHByb21vdGVk" + + "IGFuZCBzdGFydCBydW5uaW5nLiBFbnRyaWVzIHdpbGwgb25seSBhcHBlYXIgaGVyZSB3aGVuIHNlcmlh" + + "bGl6aW5nIGEgc2NoZWR1bGVyCiBfYWZ0ZXJfIG1hbnVhbGx5IHNjaGVkdWxpbmcgYSBjb21tYW5kIGJ1" + + "dCBfYmVmb3JlXyBjYWxsaW5nIHNjaGVkdWxlci5ydW4oKQoKDAoFBAICAAQSAzACCgoMCgUEAgIABhID" + + "MAsaCgwKBQQCAgABEgMwGyoKDAoFBAICAAMSAzAtLgoLCgQEAgIBEgMxAjAKDAoFBAICAQQSAzECCgoM" + + "CgUEAgIBBhIDMQsaCgwKBQQCAgEBEgMxGysKDAoFBAICAQMSAzEuLwpPCgQEAgICEgM0AhoaQiBIb3cg", + "bXVjaCB0aW1lIHRoZSBzY2hlZHVsZXIgdG9vayBpbiBpdHMgbGFzdCBgcnVuKClgIGludm9jYXRpb24u" + + "CgoMCgUEAgICBRIDNAIICgwKBQQCAgIBEgM0CRUKDAoFBAICAgMSAzQYGWIGcHJvdG8z"); static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom( @@ -52,11 +65,11 @@ public final class Scheduler { 56, 49, "ProtobufRequireableResource", "wpi.proto.ProtobufRequireableResource"); static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = - descriptor.internalContainedType(108, 186, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + descriptor.internalContainedType(108, 320, "ProtobufCommand", "wpi.proto.ProtobufCommand"); static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType( - 297, 159, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + 431, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); /** * @return this proto file's descriptor. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java index ab68c4f02de..eef015c392c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java @@ -44,5 +44,7 @@ public void pack(ProtobufScheduler msg, Scheduler scheduler) { cp.pack(commandMessage, command); msg.addRunningCommands(commandMessage); } + + msg.setLastTimeMs(scheduler.lastRuntimeMs()); } } diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/scheduler.proto index bbeed7a5351..c8ce963a7ff 100644 --- a/commandsv3/src/main/proto/scheduler.proto +++ b/commandsv3/src/main/proto/scheduler.proto @@ -16,11 +16,30 @@ message ProtobufRequireableResource { } message ProtobufCommand { + // A unique ID for the command. + // Different invocations of the same command object have different IDs. uint32 id = 1; + + // The ID of the parent command. + // Not included in the message for top-level commands. optional uint32 parent_id = 2; + + // The name of the command. string name = 3; + + // The priority level of the command. int32 priority = 4; + + // The resources required by the command. repeated ProtobufRequireableResource requirements = 5; + + // How much time the command took to execute in its most recent run. + // Only included in a message for an actively running command. + optional double last_time_ms = 6; + + // How long the command has taken to run, in aggregate. + // Only included in a message for an actively running command. + optional double total_time_ms = 7; } message ProtobufScheduler { @@ -29,4 +48,7 @@ message ProtobufScheduler { // _after_ manually scheduling a command but _before_ calling scheduler.run() repeated ProtobufCommand queued_commands = 1; repeated ProtobufCommand running_commands = 2; + + // How much time the scheduler took in its last `run()` invocation. + double last_time_ms = 3; } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 1a57e3f46e1..875f389508e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -11,6 +11,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; +import edu.wpi.first.wpilibj.RobotController; import java.util.ArrayList; import java.util.Collections; import java.util.List; @@ -28,6 +29,7 @@ class SchedulerTest { @BeforeEach void setup() { + RobotController.setTimeSource(() -> System.nanoTime() / 1000L); scheduler = new Scheduler(); } @@ -577,6 +579,7 @@ void protobuf() { assertEquals( """ { + "lastTimeMs": %s, "queuedCommands": [{ "priority": 0, "id": %s, @@ -587,6 +590,8 @@ void protobuf() { "name": "Command 2" }], "runningCommands": [{ + "lastTimeMs": %s, + "totalTimeMs": %s, "priority": 0, "id": %s, "name": "Group", @@ -594,6 +599,8 @@ void protobuf() { "name": "The Resource" }] }, { + "lastTimeMs": %s, + "totalTimeMs": %s, "priority": 0, "id": %s, "parentId": %s, @@ -602,6 +609,8 @@ void protobuf() { "name": "The Resource" }] }, { + "lastTimeMs": %s, + "totalTimeMs": %s, "priority": 0, "id": %s, "parentId": %s, @@ -610,6 +619,8 @@ void protobuf() { "name": "The Resource" }] }, { + "lastTimeMs": %s, + "totalTimeMs": %s, "priority": 0, "id": %s, "parentId": %s, @@ -620,15 +631,33 @@ void protobuf() { }] }""" .formatted( - System.identityHashCode(scheduledCommand1), // id - System.identityHashCode(scheduledCommand2), // id - System.identityHashCode(group), // id - System.identityHashCode(c2Command), // id - System.identityHashCode(group), // parent - System.identityHashCode(c3Command), // id - System.identityHashCode(c2Command), // parent - System.identityHashCode(parkCommand), // id - System.identityHashCode(c3Command) // parent + // Scheduler data + scheduler.lastRuntimeMs(), + + // On deck commands + scheduler.runId(scheduledCommand1), + scheduler.runId(scheduledCommand2), + + // Running commands + scheduler.lastRuntimeMs(group), + scheduler.totalRuntimeMs(group), + scheduler.runId(group), // id + // top-level command, no parent ID + + scheduler.lastRuntimeMs(c2Command), + scheduler.totalRuntimeMs(c2Command), + scheduler.runId(c2Command), // id + scheduler.runId(group), // parent + + scheduler.lastRuntimeMs(c3Command), + scheduler.totalRuntimeMs(c3Command), + scheduler.runId(c3Command), // id + scheduler.runId(c2Command), // parent + + scheduler.lastRuntimeMs(parkCommand), + scheduler.totalRuntimeMs(parkCommand), + scheduler.runId(parkCommand), // id + scheduler.runId(c3Command) // parent ), messageJson); } diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index a059d41ef5d..6e323bc862e 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -133,6 +133,12 @@ subsystems; a command at a particular index may require different subsystems tha command at that same index that’s running at a later point in time, making data analysis in AdvantageScope difficult since we can’t rely on consistent ordering. +Telemetry will send lists of the on-deck and running commands. Commands in those lists will appear +as an ID number, parent command ID (if any; top level commands have no parent), name, names of +the required resources, priority level, last time to process, and total processing time. Separate +runs of the same command object have different ID numbers and processing time data. The total time +spent in the scheduler loop will also be included, but not the aggregate total of _all_ loops. + ## Non-Goals ### Preemptive Multitasking @@ -304,14 +310,14 @@ caused by loop timings for deeply nested commands. Scheduler state is serialized using protobuf. The scheduler will send a list of the currently queued commands and a list of the current running commands. Commands are serialized as (id: uint32, -parent_id: uint32, name: string, priority: int32, required_resources: string array). Consumers can -use the `id` and `parent_id` attributes to reconstruct the tree structure, if desired. `id` and -`parent_id` marginally increase the size of serialized data, but make the schema and deserialization -quite simple. +parent_id: uint32, name: string, priority: int32, required_resources: string array, +last_time_ms: double, total_time_ms: double). Consumers can use the `id` and `parent_id` attributes +to reconstruct the tree structure, if desired. `id` and `parent_id` marginally increase the size of +serialized data, but make the schema and deserialization quite simple. Command IDs are the Java system identity hashcode (_not_ object hashcode, which can be overridden -and be identical for different command objects). If a command has no parent, its parent ID will be -set to zero. +and be identical for different command objects). If a command has no parent, no parent ID will +appear in its message. Records in the serialized output will be ordered by scheduling order. As a result, child commands will always appear _after_ their parent. @@ -329,10 +335,10 @@ Command theCommand() { } ``` -Telemetry for the scheduler would look like: +Telemetry for commands in the scheduler would look like: -| `id` | `parent_id` | `name` | `priority` | `required_resources` | -|--------|-------------|---------------------------|------------|----------------------| -| 347123 | 0 | "(Command 1 & Command 2)" | 2 | ["R1", "R2"] | -| 998712 | 347123 | "Command 1" | 1 | ["R1"] | -| 591564 | 347123 | "Command 2" | 2 | ["R2"] | +| `id` | `parent_id` | `name` | `priority` | `required_resources` | `last_time_ms` | `total_time_ms` | +|--------|-------------|---------------------------|------------|----------------------|----------------|-----------------| +| 347123 | -- | "(Command 1 & Command 2)" | 2 | ["R1", "R2"] | 0.210 | 5.122 | +| 998712 | 347123 | "Command 1" | 1 | ["R1"] | 0.051 | 1.241 | +| 591564 | 347123 | "Command 2" | 2 | ["R2"] | 0.108 | 3.249 | From 9813dd327ef13938527d86e407715cbd52ea64f1 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 13 May 2025 18:24:43 -0400 Subject: [PATCH 019/153] Throw when calling methods on unmounted coroutines Improve error messaging when yielding in a synchronized block or method; the default "Pinned: MONITOR" message isn't very helpful Fix a bug where top-level continuations were not unmounted --- .../org/wpilib/commands3/Continuation.java | 19 +++++ .../java/org/wpilib/commands3/Coroutine.java | 49 +++++++++++- .../java/org/wpilib/commands3/Scheduler.java | 3 + .../org/wpilib/commands3/CoroutineTest.java | 75 +++++++++++++++++++ design-docs/commands-v3.md | 19 +++++ 5 files changed, 164 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 80d96d197a3..b1f90434644 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -21,6 +21,7 @@ public final class Continuation { private static final MethodHandle IS_DONE; private static final MethodHandle java_lang_thread_setContinuation; + private static final MethodHandle java_lang_thread_getContinuation; static { try { @@ -63,6 +64,11 @@ public final class Continuation { Thread.class, "setContinuation", MethodType.methodType(void.class, Continuation.jdk_internal_vm_Continuation)); + + java_lang_thread_getContinuation = + lookup.findVirtual( + Thread.class, + "getContinuation", MethodType.methodType(Continuation.jdk_internal_vm_Continuation)); } catch (Throwable t) { throw new ExceptionInInitializerError(t); } @@ -95,6 +101,8 @@ public Continuation(ContinuationScope scope, Runnable target) { public static boolean yield(ContinuationScope scope) { try { return (boolean) YIELD.invoke(scope.continuationScope); + } catch (RuntimeException e) { + throw e; } catch (Throwable t) { throw new RuntimeException(t); } @@ -163,4 +171,15 @@ public String toString() { public boolean yield() { return Continuation.yield(scope); } + + boolean isMounted() { + try { + Object mountedContinuation = java_lang_thread_getContinuation.invoke(Thread.currentThread()); + return mountedContinuation == continuation; + } catch (RuntimeException e) { + throw e; + } catch (Throwable t) { + throw new RuntimeException(t); + } + } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 6dedabf6fd3..27e4f6f9d5e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -35,7 +35,25 @@ public final class Coroutine { * @return true */ public boolean yield() { - return backingContinuation.yield(); + requireMounted(); + + try { + return backingContinuation.yield(); + } catch (IllegalStateException e) { + if (e.getMessage().equals("Pinned: MONITOR")) { + // Yielding inside a synchronized block or method + // Throw with an error message that's more helpful for our users + throw new IllegalStateException( + "Coroutine.yield() cannot be called inside a synchronized block or method. " + + "Consider using a Lock instead of synchronized, " + + "or rewrite your code to avoid locks and mutexes altogether.", + e + ); + } else { + // rethrow + throw e; + } + } } /** @@ -44,6 +62,8 @@ public boolean yield() { */ @SuppressWarnings("InfiniteLoopStatement") public void park() { + requireMounted(); + while (true) { Coroutine.this.yield(); } @@ -69,6 +89,8 @@ public void park() { * @param commands The commands to fork. */ public void fork(Command... commands) { + requireMounted(); + // Shorthand; this is handy for user-defined compositions for (var command : commands) { scheduler.schedule(command); @@ -84,6 +106,8 @@ public void fork(Command... commands) { * command */ public void await(Command command) { + requireMounted(); + if (!scheduler.isScheduledOrRunning(command)) { scheduler.schedule(command); } @@ -103,6 +127,8 @@ public void await(Command command) { * @throws IllegalArgumentException if any of the commands conflict with each other */ public void awaitAll(Collection commands) { + requireMounted(); + validateNoConflicts(commands); // Schedule anything that's not already queued or running @@ -138,6 +164,8 @@ public void awaitAll(Command... commands) { * @throws IllegalArgumentException if any of the commands conflict with each other */ public void awaitAny(Collection commands) { + requireMounted(); + validateNoConflicts(commands); // Schedule anything that's not already queued or running @@ -215,6 +243,8 @@ private static void validateNoConflicts(Collection commands) { * @param duration the duration of time to wait */ public void wait(Time duration) { + requireMounted(); + await(new WaitCommand(duration)); } @@ -230,6 +260,23 @@ public Scheduler scheduler() { return scheduler; } + private boolean isMounted() { + return backingContinuation.isMounted(); + } + + private void requireMounted() { + // Note: attempting to yield() outside a command will already throw an error due to the + // continuation being unmounted, but other actions like forking and awaiting should also + // throw errors. For consistent messaging, we use this helper in all places, not just the + // ones that interact with the backing continuation. + + if (isMounted()) { + return; + } + + throw new IllegalStateException("Coroutines can only be used while running in a command"); + } + // Package-private for interaction with the scheduler. // These functions are not intended for team use. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index ac8074cc35b..92fbc58d102 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -430,9 +430,12 @@ private void runCommand(CommandState state) { // Remove the command we just ran from the top of the stack executingCommands.pop(); } + if (previousState != null) { // Remount the parent command, if there is one previousState.coroutine().mount(); + } else { + Continuation.mountContinuation(null); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index c056aa59253..d4305349114 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -4,8 +4,14 @@ package org.wpilib.commands3; +import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; +import java.util.concurrent.locks.Lock; +import java.util.concurrent.locks.ReentrantLock; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -37,4 +43,73 @@ void forkMany() { assertTrue(scheduler.isRunning(b)); assertTrue(scheduler.isRunning(c)); } + + @Test + void yieldInSynchronizedBlock() { + Object mutex = new Object(); + AtomicInteger i = new AtomicInteger(0); + + var yieldInSynchronized = Command.noRequirements(co -> { + while (true) { + synchronized (mutex) { + i.incrementAndGet(); + co.yield(); + } + } + }).named("Yield In Synchronized Block"); + + scheduler.schedule(yieldInSynchronized); + + try { + scheduler.run(); + fail("Monitor pinned exception should have been thrown"); + } catch (IllegalStateException expected) { + assertEquals( + "Coroutine.yield() cannot be called inside a synchronized block or method. " + + "Consider using a Lock instead of synchronized, " + + "or rewrite your code to avoid locks and mutexes altogether.", + expected.getMessage()); + } + } + + @Test + void yieldInLockBody() { + Lock lock = new ReentrantLock(); + AtomicInteger i = new AtomicInteger(0); + + var yieldInLock = Command.noRequirements(co -> { + while (true) { + lock.lock(); + try { + i.incrementAndGet(); + co.yield(); + } finally { + lock.unlock(); + } + } + }).named("Increment In Lock Block"); + + scheduler.schedule(yieldInLock); + scheduler.run(); + assertEquals(1, i.get()); + } + + @Test + void coroutineEscapingCommand() { + AtomicReference escapeeCallback = new AtomicReference<>(); + + var badCommand = Command.noRequirements(co -> { + escapeeCallback.set(co::yield); + }).named("Bad Command"); + + scheduler.schedule(badCommand); + scheduler.run(); + + try { + escapeeCallback.get().run(); + fail("Calling coroutine.yield() outside of a command should error"); + } catch (IllegalStateException expected) { + assertEquals("Coroutines can only be used while running in a command", expected.getMessage()); + } + } } diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 6e323bc862e..2f5b5d81f24 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -155,6 +155,25 @@ single-threaded environment. All commands will be run by a single thread, which the same thread on which commands are scheduled and canceled via triggers. No guarantees are made for stability or proper functioning if used in a multithreaded environment. +### Unbounded use of coroutines + +Coroutines are intended to be used within the context of a running command or sideloaded periodic +function, and rely on their backing continuations to be mounted in order to run. Using a coroutine +outside its command makes no sense, and an error will be thrown if attempting to do so: + +```java +Coroutine coroutine; +var badCommand = Command.noRequirements(co -> { + coroutine = co; +}).named("Do not do this"); + +Scheduler.getInstance().schedule(badCommand); +Scheduler.getInstance().run(); + +// Doing anything with a captured coroutine will throw an error +co.fork(...); // IllegalStateException +co.yield(); // IllegalStateException +``` ## Implementation Details From eea410be52f4936aa242a6fdd0d2860194c6e052 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 14 May 2025 21:56:46 -0400 Subject: [PATCH 020/153] Fix copy-paste error from v2 cmake setup --- ...newcommands-config.cmake.in => commandsv3-config.cmake.in} | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) rename commandsv3/{wpilibnewcommands-config.cmake.in => commandsv3-config.cmake.in} (70%) diff --git a/commandsv3/wpilibnewcommands-config.cmake.in b/commandsv3/commandsv3-config.cmake.in similarity index 70% rename from commandsv3/wpilibnewcommands-config.cmake.in rename to commandsv3/commandsv3-config.cmake.in index b26b9a7a555..8b988a1c95a 100644 --- a/commandsv3/wpilibnewcommands-config.cmake.in +++ b/commandsv3/commandsv3-config.cmake.in @@ -8,7 +8,7 @@ include(CMakeFindDependencyMacro) @WPIMATH_DEP_REPLACE@ @FILENAME_DEP_REPLACE@ -include(${SELF_DIR}/wpilibnewcommands.cmake) +include(${SELF_DIR}/commandsv3.cmake) if(@WITH_JAVA@) - include(${SELF_DIR}/wpilibNewCommands_jar.cmake) + include(${SELF_DIR}/commandsv3_jar.cmake) endif() From f9dbda31d2c1e98b7fb297dd67131a716ded0080 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 15 May 2025 17:50:00 -0400 Subject: [PATCH 021/153] Track mounted continuation in wrapper --- .../org/wpilib/commands3/Continuation.java | 23 ++++++++++++------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index b1f90434644..ee60fb23c57 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -23,6 +23,8 @@ public final class Continuation { private static final MethodHandle java_lang_thread_setContinuation; private static final MethodHandle java_lang_thread_getContinuation; + private static final ThreadLocal mountedContinuation = new ThreadLocal<>(); + static { try { jdk_internal_vm_Continuation = Class.forName("jdk.internal.vm.Continuation"); @@ -149,8 +151,10 @@ public static void mountContinuation(Continuation continuation) { try { if (continuation == null) { java_lang_thread_setContinuation.invoke(Thread.currentThread(), null); + mountedContinuation.remove(); } else { java_lang_thread_setContinuation.invoke(Thread.currentThread(), continuation.continuation); + mountedContinuation.set(continuation); } } catch (Throwable t) { // Anything thrown internally by Thread.setContinuation. @@ -160,6 +164,16 @@ public static void mountContinuation(Continuation continuation) { } } + /** + * Gets the currently mounted continuation. This is thread-local value; calling this method on two + * different threads will give two different results. + * + * @return The continuation mounted on the current thread. + */ + public static Continuation getMountedContinuation() { + return mountedContinuation.get(); + } + @Override public String toString() { return continuation.toString(); @@ -173,13 +187,6 @@ public boolean yield() { } boolean isMounted() { - try { - Object mountedContinuation = java_lang_thread_getContinuation.invoke(Thread.currentThread()); - return mountedContinuation == continuation; - } catch (RuntimeException e) { - throw e; - } catch (Throwable t) { - throw new RuntimeException(t); - } + return this == getMountedContinuation(); } } From 62925d632057fb08caac11e43523e1d7c735f844 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 15 May 2025 17:50:50 -0400 Subject: [PATCH 022/153] Clean up after awaitAny Spec is to cancel anything still running after returning, but the impl didn't do that --- .../java/org/wpilib/commands3/Coroutine.java | 2 ++ .../org/wpilib/commands3/CoroutineTest.java | 36 ++++++++++++++++++- 2 files changed, 37 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 27e4f6f9d5e..9b5ef0cbbfd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -178,6 +178,8 @@ public void awaitAny(Collection commands) { while (commands.stream().allMatch(scheduler::isScheduledOrRunning)) { this.yield(); } + + commands.forEach(scheduler::cancel); } /** diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index d4305349114..1417a79b093 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -8,6 +8,9 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; +import edu.wpi.first.wpilibj.RobotController; +import java.util.Set; +import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; import java.util.concurrent.atomic.AtomicReference; import java.util.concurrent.locks.Lock; @@ -23,9 +26,9 @@ class CoroutineTest { void setup() { scheduler = new Scheduler(); scope = new ContinuationScope("Test Scope"); + RobotController.setTimeSource(() -> System.nanoTime() / 1000L); } - @Test void forkMany() { var a = new NullCommand(); @@ -112,4 +115,35 @@ void coroutineEscapingCommand() { assertEquals("Coroutines can only be used while running in a command", expected.getMessage()); } } + + @Test + void awaitAnyCleansUp() { + AtomicBoolean firstRan = new AtomicBoolean(false); + AtomicBoolean secondRan = new AtomicBoolean(false); + AtomicBoolean ranAfterAwait = new AtomicBoolean(false); + + var firstInner = Command.noRequirements(c2 -> firstRan.set(true)).named("First"); + var secondInner = Command.noRequirements(c2 -> { + secondRan.set(true); + c2.park(); + }).named("Second"); + + var outer = Command.noRequirements(co -> { + co.awaitAny(firstInner, secondInner); + + ranAfterAwait.set(true); + co.park(); // prevent exiting + }).named("Command"); + + scheduler.schedule(outer); + scheduler.run(); + + // Everything should have run... + assertTrue(firstRan.get()); + assertTrue(secondRan.get()); + assertTrue(ranAfterAwait.get()); + + // But only the outer command should still be running; secondInner should have been cancelled + assertEquals(Set.of(outer), scheduler.getRunningCommands()); + } } From dfde0c598e81427844ab483c46af41f63fd1e814 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 7 Jun 2025 17:17:12 -0400 Subject: [PATCH 023/153] Command-local trigger bindings Bindings created within a running command are scoped to that command's lifetime. The bindings are deleted when the command exits. Bindings created outside of a running command are considered to be globally scoped and will always be active. --- .../java/org/wpilib/commands3/Scheduler.java | 2 +- .../org/wpilib/commands3/button/Binding.java | 19 +++++ .../wpilib/commands3/button/BindingScope.java | 44 +++++++++++ .../wpilib/commands3/button/BindingType.java | 39 ++++++++++ .../org/wpilib/commands3/button/Trigger.java | 75 +++++++++---------- .../wpilib/commands3/button/TriggerTest.java | 30 ++++++++ 6 files changed, 168 insertions(+), 41 deletions(-) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 92fbc58d102..f9cfb2c0713 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -466,7 +466,7 @@ private CommandState currentState() { * * @return the currently executing command */ - private Command currentCommand() { + public Command currentCommand() { var state = currentState(); if (state == null) { return null; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java b/commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java new file mode 100644 index 00000000000..582188473ef --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java @@ -0,0 +1,19 @@ +package org.wpilib.commands3.button; + +import edu.wpi.first.util.ErrorMessages; +import org.wpilib.commands3.Command; + +/** + * A single trigger binding. + * + * @param scope The scope in which the binding is active. + * @param type The type of binding; or, when the bound command should run + * @param command The bound command. Cannot be null. + */ +record Binding(BindingScope scope, BindingType type, Command command) { + public Binding { + ErrorMessages.requireNonNullParam(scope, "scope", "Binding"); + ErrorMessages.requireNonNullParam(type, "type", "Binding"); + ErrorMessages.requireNonNullParam(command, "command", "Binding"); + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java new file mode 100644 index 00000000000..ab9b3f52a99 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java @@ -0,0 +1,44 @@ +package org.wpilib.commands3.button; + +import org.wpilib.commands3.Command; +import org.wpilib.commands3.Scheduler; + +/** + * A scope for when a binding is live. Bindings tied to a scope must be deleted when the scope + * becomes inactive. + */ +sealed interface BindingScope { + /** + * Checks if the scope is active. Bindings for inactive scopes are removed from the scheduler. + * + * @return True if the scope is still active, false if not. + */ + boolean active(); + + /** + * A global binding scope. Bindings in this scope are always active. + */ + final class Global implements BindingScope { + // No reason not to be a singleton. + public static final Global INSTANCE = new Global(); + + @Override + public boolean active() { + return true; + } + } + + /** + * A binding scoped to the lifetime of a specific command. This should be used when a binding + * is created within a command, tying the lifetime of the binding to the declaring command. + * + * @param scheduler The scheduler managing the command. + * @param command The command being scoped to. + */ + record ForCommand(Scheduler scheduler, Command command) implements BindingScope { + @Override + public boolean active() { + return scheduler.isRunning(command); + } + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java new file mode 100644 index 00000000000..19292f09972 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java @@ -0,0 +1,39 @@ +package org.wpilib.commands3.button; + +/** + * Describes when a command bound to a trigger should run. + */ +enum BindingType { + /** + * Schedules (forks) a command on a rising edge signal. The command will run until it completes + * or is interrupted by another command requiring the same resources. + */ + SCHEDULE_ON_RISING_EDGE, + /** + * Schedules (forks) a command on a falling edge signal. The command will run until it completes + * or is interrupted by another command requiring the same resources. + */ + SCHEDULE_ON_FALLING_EDGE, + /** + * Schedules (forks) a command on a rising edge signal. If the command is still running on the + * next rising edge, it will be cancelled then; otherwise, it will be scheduled again. + */ + TOGGLE_ON_RISING_EDGE, + /** + * Schedules (forks) a command on a falling edge signal. If the command is still running on the + * next falling edge, it will be cancelled then; otherwise, it will be scheduled again. + */ + TOGGLE_ON_FALLING_EDGE, + /** + * Schedules a command on a rising edge signal. If the command is still running on the next + * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which + * would allow it to continue to run. + */ + RUN_WHILE_HIGH, + /** + * Schedules a command on a falling edge signal. If the command is still running on the next + * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which + * would allow it to continue to run. + */ + RUN_WHILE_LOW +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java index b7f6286ad12..9abe11b9f99 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java @@ -32,7 +32,7 @@ public class Trigger implements BooleanSupplier { private final EventLoop m_loop; private final Scheduler scheduler; private Signal m_previousSignal = null; - private final Map> m_bindings = new EnumMap<>(BindingType.class); + private final Map> m_bindings = new EnumMap<>(BindingType.class); private final Runnable m_eventLoopCallback = this::poll; /** @@ -40,45 +40,14 @@ public class Trigger implements BooleanSupplier { * first run, when the previous signal value is undefined and unknown. */ private enum Signal { - /** The signal is high. */ - HIGH, - /** The signal is low. */ - LOW - } - - private enum BindingType { - /** - * Schedules (forks) a command on a rising edge signal. The command will run until it completes - * or is interrupted by another command requiring the same resources. - */ - SCHEDULE_ON_RISING_EDGE, /** - * Schedules (forks) a command on a falling edge signal. The command will run until it completes - * or is interrupted by another command requiring the same resources. + * The signal is high. */ - SCHEDULE_ON_FALLING_EDGE, - /** - * Schedules (forks) a command on a rising edge signal. If the command is still running on the - * next rising edge, it will be cancelled then; otherwise, it will be scheduled again. - */ - TOGGLE_ON_RISING_EDGE, - /** - * Schedules (forks) a command on a falling edge signal. If the command is still running on the - * next falling edge, it will be cancelled then; otherwise, it will be scheduled again. - */ - TOGGLE_ON_FALLING_EDGE, - /** - * Schedules a command on a rising edge signal. If the command is still running on the next - * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which - * would allow it to continue to run. - */ - RUN_WHILE_HIGH, + HIGH, /** - * Schedules a command on a falling edge signal. If the command is still running on the next - * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which - * would allow it to continue to run. + * The signal is low. */ - RUN_WHILE_LOW + LOW } public Trigger(Scheduler scheduler, BooleanSupplier condition) { @@ -254,6 +223,11 @@ public boolean getAsBoolean() { } private void poll() { + // Clear bindings that no longer need to run + // This should always be checked, regardless of signal change, since bindings may be scoped + // and those scopes may become inactive. + clearStaleBindings(); + var signal = signal(); if (signal == m_previousSignal) { @@ -288,13 +262,23 @@ private Signal signal() { } } + /** + * Removes bindings in inactive scopes. + */ + private void clearStaleBindings() { + m_bindings.forEach(((_bindingType, bindings) -> { + bindings.removeIf(binding -> !binding.scope().active()); + })); + } + /** * Schedules all commands bound to the given binding type. * * @param bindingType the binding type to schedule */ private void scheduleBindings(BindingType bindingType) { - m_bindings.getOrDefault(bindingType, List.of()).forEach(scheduler::schedule); + m_bindings.getOrDefault(bindingType, List.of()) + .forEach(binding -> scheduler.schedule(binding.command())); } /** @@ -303,7 +287,8 @@ private void scheduleBindings(BindingType bindingType) { * @param bindingType the binding type to cancel */ private void cancelBindings(BindingType bindingType) { - m_bindings.getOrDefault(bindingType, List.of()).forEach(scheduler::cancel); + m_bindings.getOrDefault(bindingType, List.of()) + .forEach(binding -> scheduler.cancel(binding.command())); } /** @@ -316,7 +301,8 @@ private void toggleBindings(BindingType bindingType) { m_bindings .getOrDefault(bindingType, List.of()) .forEach( - command -> { + binding -> { + var command = binding.command(); if (scheduler.isScheduledOrRunning(command)) { scheduler.cancel(command); } else { @@ -326,7 +312,16 @@ private void toggleBindings(BindingType bindingType) { } private void addBinding(BindingType bindingType, Command command) { - m_bindings.computeIfAbsent(bindingType, _k -> new ArrayList<>()).add(command); + BindingScope scope = switch (scheduler.currentCommand()) { + // A command is creating a binding - make it scoped to that specific command + case Command c -> new BindingScope.ForCommand(scheduler, c); + + // Creating a binding outside a command - it's global in scope + case null -> BindingScope.Global.INSTANCE; + }; + + m_bindings.computeIfAbsent(bindingType, _k -> new ArrayList<>()) + .add(new Binding(scope, bindingType, command)); // Ensure this trigger is bound to the event loop. NOP if already bound m_loop.bind(m_eventLoopCallback); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java index 733fbc35881..3d1cddfc885 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java @@ -127,4 +127,34 @@ void toggleOnFalse() { scheduler.run(); assertFalse(scheduler.isRunning(command)); } + + @Test + void commandScoping() { + var innerRan = new AtomicBoolean(false); + var innerSignal = new AtomicBoolean(false); + + var inner = Command.noRequirements(co -> { + while (true) { + innerRan.set(true); + co.park(); + } + }).named("Inner"); + + var outer = Command.noRequirements(co -> { + new Trigger(scheduler, innerSignal::get).onTrue(inner); + co.yield(); + }).named("Outer"); + + scheduler.schedule(outer); + scheduler.run(); + assertFalse(innerRan.get(), "The bound command should not run before the signal is set"); + + innerSignal.set(true); + scheduler.run(); + assertTrue(innerRan.get(), "The nested trigger should have run the bound command"); + + innerRan.set(false); + scheduler.run(); + assertFalse(innerRan.get(), "Trigger should not have fired again"); + } } From 063bb2717bad30707e254fbe939b4d5027f38cfb Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:37:57 -0400 Subject: [PATCH 024/153] Report scheduling trace for exceptions thrown by commands Instead of a fairly useless backtrace pointing to where user code called `Scheduler.run()`, we save the stack trace at command binding time (either through `Trigger.onTrue()` or related methods, or by manually calling `Scheduler.schedule()` in user code or forking in a coroutine) and inject that stack trace into the thrown exception. --- .../commands3/{button => }/Binding.java | 13 +++- .../commands3/{button => }/BindingScope.java | 13 ++-- .../commands3/{button => }/BindingType.java | 7 +- .../org/wpilib/commands3/CommandState.java | 12 +++- .../wpilib/commands3/CommandTraceHelper.java | 71 +++++++++++++++++++ .../java/org/wpilib/commands3/Scheduler.java | 25 ++++++- .../commands3/{button => }/Trigger.java | 17 ++--- .../commands3/button/CommandGenericHID.java | 1 + .../commands3/button/CommandJoystick.java | 1 + .../button/CommandPS4Controller.java | 1 + .../button/CommandPS5Controller.java | 1 + .../button/CommandStadiaController.java | 1 + .../button/CommandXboxController.java | 1 + .../commands3/button/InternalButton.java | 1 + .../commands3/button/JoystickButton.java | 1 + .../commands3/button/NetworkButton.java | 1 + .../wpilib/commands3/button/POVButton.java | 1 + .../commands3/button/RobotModeTriggers.java | 1 + .../org/wpilib/commands3/SchedulerTest.java | 60 +++++++++++++++- .../commands3/{button => }/TriggerTest.java | 5 +- 20 files changed, 210 insertions(+), 24 deletions(-) rename commandsv3/src/main/java/org/wpilib/commands3/{button => }/Binding.java (51%) rename commandsv3/src/main/java/org/wpilib/commands3/{button => }/BindingScope.java (83%) rename commandsv3/src/main/java/org/wpilib/commands3/{button => }/BindingType.java (87%) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java rename commandsv3/src/main/java/org/wpilib/commands3/{button => }/Trigger.java (96%) rename commandsv3/src/test/java/org/wpilib/commands3/{button => }/TriggerTest.java (96%) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java similarity index 51% rename from commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java rename to commandsv3/src/main/java/org/wpilib/commands3/Binding.java index 582188473ef..8e5c40e648f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/Binding.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java @@ -1,7 +1,6 @@ -package org.wpilib.commands3.button; +package org.wpilib.commands3; import edu.wpi.first.util.ErrorMessages; -import org.wpilib.commands3.Command; /** * A single trigger binding. @@ -9,8 +8,16 @@ * @param scope The scope in which the binding is active. * @param type The type of binding; or, when the bound command should run * @param command The bound command. Cannot be null. + * @param frames The stack frames when the binding was created. Used for telemetry and error + * reporting so if a command throws an exception, we can tell users where that + * command was bound instead of giving a fairly useless backtrace of the command + * framework. */ -record Binding(BindingScope scope, BindingType type, Command command) { +record Binding( + BindingScope scope, + BindingType type, + Command command, + StackTraceElement[] frames) { public Binding { ErrorMessages.requireNonNullParam(scope, "scope", "Binding"); ErrorMessages.requireNonNullParam(type, "type", "Binding"); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java similarity index 83% rename from commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java rename to commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java index ab9b3f52a99..d27ad85e70a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java @@ -1,7 +1,4 @@ -package org.wpilib.commands3.button; - -import org.wpilib.commands3.Command; -import org.wpilib.commands3.Scheduler; +package org.wpilib.commands3; /** * A scope for when a binding is live. Bindings tied to a scope must be deleted when the scope @@ -15,6 +12,14 @@ sealed interface BindingScope { */ boolean active(); + static BindingScope global() { + return Global.INSTANCE; + } + + static BindingScope forCommand(Scheduler scheduler, Command command) { + return new ForCommand(scheduler, command); + } + /** * A global binding scope. Bindings in this scope are always active. */ diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java similarity index 87% rename from commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java rename to commandsv3/src/main/java/org/wpilib/commands3/BindingType.java index 19292f09972..28bd02510dc 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/BindingType.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java @@ -1,9 +1,14 @@ -package org.wpilib.commands3.button; +package org.wpilib.commands3; /** * Describes when a command bound to a trigger should run. */ enum BindingType { + /** + * An immediate or manual binding created when calling {@link Scheduler#schedule(Command)} + * directly, without using a trigger to bind it to a signal. + */ + IMMEDIATE, /** * Schedules (forks) a command on a rising edge signal. The command will run until it completes * or is interrupted by another command requiring the same resources. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index 392266ac553..d49dc371a87 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -9,6 +9,7 @@ final class CommandState { private final Command command; private final Command parent; private final Coroutine coroutine; + private final Binding binding; // may be null private double lastRuntimeMs = -1; private double totalRuntimeMs = 0; private final int id = System.identityHashCode(this); @@ -21,11 +22,15 @@ final class CommandState { * that invoked the schedule() call; in this manner, an ancestry tree can be built, where each * {@code CommandState} object references a parent node in the tree. * @param coroutine The coroutine to which the command is bound. + * @param scheduleFrames The stack frames for the schedule site; that is, the backtrace of the + * code that caused the command to be scheduled. These let us report better traces when + * commands encounter exceptions. */ - CommandState(Command command, Command parent, Coroutine coroutine) { + CommandState(Command command, Command parent, Coroutine coroutine, Binding binding) { this.command = command; this.parent = parent; this.coroutine = coroutine; + this.binding = binding; // may be null } public Command command() { @@ -40,6 +45,11 @@ public Coroutine coroutine() { return coroutine; } + // may return null + public Binding binding() { + return binding; + } + /** * How long the command took to run the last time it executed. Defaults to -1 if the command has * not run at least once. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java new file mode 100644 index 00000000000..f3864a8f9d8 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -0,0 +1,71 @@ +package org.wpilib.commands3; + +import java.util.ArrayList; +import java.util.List; +import java.util.stream.Stream; + +final class CommandTraceHelper { + private CommandTraceHelper() { + // Utility class + } + + /** + * Creates a modified stack trace where the trace of the scheduling code replaces the trace of + * the internal scheduler logic. + * + * @param commandExceptionTrace The trace of the exception raised during command execution. + * @param commandScheduleTrace The trace of when the command was scheduled. + * @return A new array of stack trace elements. + */ + public static StackTraceElement[] modifyTrace( + StackTraceElement[] commandExceptionTrace, + StackTraceElement[] commandScheduleTrace) { + + List frames = new ArrayList<>(); + + List filteredClasses = List.of( + Coroutine.class.getName(), + Continuation.class.getName(), + Scheduler.class.getName(), + "org.wpilib.commands3.CommandBuilder$1", + "jdk.internal.vm.Continuation" + ); + + boolean sawRun = false; + for (var exceptionFrame : commandExceptionTrace) { + if (!filteredClasses.contains(exceptionFrame.getClassName())) { + frames.add(exceptionFrame); + } + + // Inject the schedule trace immediately after the line of user code that called Scheduler.run + if (sawRun) { + // Inject a marker frame just so there's a distinction between the command's code and the + // code that scheduled it, since they occur asynchronously + frames.add( + new StackTraceElement("=== Command Binding Trace ===", "", "", -1) + ); + + // Drop internal trigger frames, since they're not helpful for users. + // The first frame here should be the line of user code that bound the command to a trigger. + Stream.of(commandScheduleTrace) + .dropWhile(frame -> { + return frame.getClassName().equals(Trigger.class.getName()) || + (frame.getClassName().equals(Scheduler.class.getName()) + && frame.getMethodName().equals("schedule")); + }) + .filter(frame -> { + return !filteredClasses.contains(frame.getClassName()); + }) + .forEach(frames::add); + break; + } + + if (exceptionFrame.getClassName().equals("org.wpilib.commands3.Scheduler") + && exceptionFrame.getMethodName().equals("run")) { + sawRun = true; + } + } + + return frames.toArray(StackTraceElement[]::new); + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index f9cfb2c0713..7eab94a335d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -182,6 +182,20 @@ public enum ScheduleResult { * scheduled another command that shares at least one required resource */ public ScheduleResult schedule(Command command) { + var binding = new Binding( + BindingScope.global(), + BindingType.IMMEDIATE, + command, + new Throwable().getStackTrace() + ); + + return schedule(binding); + } + + // Package-private for use by Trigger + ScheduleResult schedule(Binding binding) { + var command = binding.command(); + if (isScheduledOrRunning(command)) { return ScheduleResult.ALREADY_RUNNING; } @@ -207,7 +221,11 @@ public ScheduleResult schedule(Command command) { // so at this point we're guaranteed to be >= priority than anything already on deck evictConflictingOnDeckCommands(command); - var state = new CommandState(command, currentCommand(), buildCoroutine(command)); + var state = new CommandState( + command, + currentCommand(), + buildCoroutine(command), + binding); if (currentState() != null) { // Scheduling a child command while running. Start it immediately instead of waiting a full @@ -421,6 +439,11 @@ private void runCommand(CommandState state) { coroutine.mount(); try { coroutine.runToYieldPoint(); + } catch (RuntimeException e) { + // Intercept the exception, inject stack frames from the schedule site, and rethrow it + var binding = state.binding(); + e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); + throw e; } finally { long endMicros = RobotController.getTime(); double elapsedMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java similarity index 96% rename from commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java rename to commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 9abe11b9f99..2e6ae8506b0 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -2,15 +2,13 @@ // 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 org.wpilib.commands3.button; +package org.wpilib.commands3; import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.units.measure.Time; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.Scheduler; import edu.wpi.first.wpilibj.event.EventLoop; import java.util.ArrayList; import java.util.EnumMap; @@ -278,7 +276,7 @@ private void clearStaleBindings() { */ private void scheduleBindings(BindingType bindingType) { m_bindings.getOrDefault(bindingType, List.of()) - .forEach(binding -> scheduler.schedule(binding.command())); + .forEach(scheduler::schedule); } /** @@ -306,7 +304,7 @@ private void toggleBindings(BindingType bindingType) { if (scheduler.isScheduledOrRunning(command)) { scheduler.cancel(command); } else { - scheduler.schedule(command); + scheduler.schedule(binding); } }); } @@ -314,14 +312,17 @@ private void toggleBindings(BindingType bindingType) { private void addBinding(BindingType bindingType, Command command) { BindingScope scope = switch (scheduler.currentCommand()) { // A command is creating a binding - make it scoped to that specific command - case Command c -> new BindingScope.ForCommand(scheduler, c); + case Command c -> BindingScope.forCommand(scheduler, c); // Creating a binding outside a command - it's global in scope - case null -> BindingScope.Global.INSTANCE; + case null -> BindingScope.global(); }; + Throwable t = new Throwable("Dummy error to get the binding trace"); + StackTraceElement[] frames = t.getStackTrace(); + m_bindings.computeIfAbsent(bindingType, _k -> new ArrayList<>()) - .add(new Binding(scope, bindingType, command)); + .add(new Binding(scope, bindingType, command, frames)); // Ensure this trigger is bound to the event loop. NOP if already bound m_loop.bind(m_eventLoopCallback); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 4a7e8140320..79a0482c601 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.GenericHID; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link GenericHID} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java index 5d13c4c9e6e..358484fbe63 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.Joystick; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link Joystick} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index 2e0b512bf46..ec75639f66a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.PS4Controller; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link PS4Controller} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 056e8466580..9d14192b5fe 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.PS5Controller; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link PS5Controller} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java index 0f85fdc83a8..b33fa11be50 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.StadiaController; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link StadiaController} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java index a5e465970c3..b92f3e78001 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj.XboxController; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; /** * A version of {@link XboxController} with {@link Trigger} factories for command-based. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java index a82ffe17f07..2378e1d054f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java @@ -5,6 +5,7 @@ package org.wpilib.commands3.button; import java.util.concurrent.atomic.AtomicBoolean; +import org.wpilib.commands3.Trigger; /** * This class is intended to be used within a program. The programmer can manually set its value. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java index b5d5b38517e..5c968a939fd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/JoystickButton.java @@ -7,6 +7,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.wpilibj.GenericHID; +import org.wpilib.commands3.Trigger; /** A {@link Trigger} that gets its state from a {@link GenericHID}. */ public class JoystickButton extends Trigger { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java index b49434f95ed..330160339e9 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/NetworkButton.java @@ -10,6 +10,7 @@ import edu.wpi.first.networktables.BooleanTopic; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableInstance; +import org.wpilib.commands3.Trigger; /** A {@link Trigger} that uses a {@link NetworkTable} boolean field. */ public class NetworkButton extends Trigger { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java index cfe843695c4..92f26a5b1c3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java @@ -7,6 +7,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.wpilibj.GenericHID; +import org.wpilib.commands3.Trigger; /** A {@link Trigger} that gets its state from a POV on a {@link GenericHID}. */ public class POVButton extends Trigger { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java b/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java index abc8c101124..6a84df1ff01 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/RobotModeTriggers.java @@ -5,6 +5,7 @@ package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.DriverStation; +import org.wpilib.commands3.Trigger; /** * A class containing static {@link Trigger} factories for running callbacks when the robot mode diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 875f389508e..edf6fde528e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -163,19 +163,75 @@ void errorDetection() { }) .named("Bad Behavior"); - scheduler.schedule(command); + new Trigger(scheduler, () -> true) + .onTrue(command); try { - scheduler.run(); fail("An exception should have been thrown"); } catch (RuntimeException e) { assertEquals("The exception", e.getMessage()); + + assertEquals("org.wpilib.commands3.SchedulerTest", e.getStackTrace()[0].getClassName()); + assertEquals("lambda$errorDetection$3", e.getStackTrace()[0].getMethodName()); + + assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); + + assertEquals(getClass().getName(), e.getStackTrace()[3].getClassName()); + assertEquals("errorDetection", e.getStackTrace()[3].getMethodName()); } catch (Throwable t) { fail("Expected a RuntimeException to be thrown, but got " + t); } } + @Test + void nestedErrorDetection() { + var command = Command.noRequirements(co -> { + co.await(Command.noRequirements(c2 -> { + new Trigger(scheduler, () -> true) + .onTrue(Command.noRequirements(c3 -> { + // Throws IndexOutOfBoundsException + new ArrayList<>(0).get(-1); + }).named("Throws IndexOutOfBounds") + ); + c2.park(); + }).named("Schedules With Trigger")); + }).named("Schedules Directly"); + + scheduler.schedule(command); + + // The first run sets up the trigger, but does not fire + // The second run will fire the trigger and cause the inner command to run and throw + scheduler.run(); + + try { + scheduler.run(); + fail("Index OOB exception expected"); + } catch (IndexOutOfBoundsException e) { + StackTraceElement[] stackTrace = e.getStackTrace(); + + assertEquals("Index -1 out of bounds for length 0", e.getMessage()); + int nestedIndex = 0; + for (; nestedIndex < stackTrace.length; nestedIndex++) { + if (stackTrace[nestedIndex].getClassName().equals(getClass().getName())) { + break; + } + } + + // user code trace for the scheduler run invocation (to `scheduler.run()` in the try block) + assertEquals("lambda$nestedErrorDetection$6", stackTrace[nestedIndex].getMethodName()); + assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 1].getMethodName()); + + // user code trace for where the command was scheduled (the `.onTrue()` line) + assertEquals("=== Command Binding Trace ===", stackTrace[nestedIndex + 2].getClassName()); + assertEquals("lambda$nestedErrorDetection$7", stackTrace[nestedIndex + 3].getMethodName()); + assertEquals("lambda$nestedErrorDetection$8", stackTrace[nestedIndex + 4].getMethodName()); + assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 5].getMethodName()); + } catch (Throwable unexpected) { + fail("Expected an IndexOutOfBoundsException to have been thrown, but got" + unexpected); + } + } + @Test void runResource() { var example = diff --git a/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java similarity index 96% rename from commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index 3d1cddfc885..329efce55dd 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/button/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -2,14 +2,11 @@ // 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 org.wpilib.commands3.button; +package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.Coroutine; -import org.wpilib.commands3.Scheduler; import java.util.concurrent.atomic.AtomicBoolean; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; From 131d4438f17c224facd2e5c83cb57df9e6a8688b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:39:41 -0400 Subject: [PATCH 025/153] Remove RobotDisabledBehavior --- .../java/org/wpilib/commands3/Command.java | 27 -------------- .../org/wpilib/commands3/CommandBuilder.java | 35 ++----------------- .../org/wpilib/commands3/IdleCommand.java | 5 --- .../org/wpilib/commands3/ParallelGroup.java | 14 -------- .../java/org/wpilib/commands3/Sequence.java | 14 -------- 5 files changed, 2 insertions(+), 93 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 52e591e3b2e..078222dece2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -133,33 +133,6 @@ default int priority() { return DEFAULT_PRIORITY; } - enum RobotDisabledBehavior { - /** - * Behavior that will prevent a command from running while the robot is disabled. A command with - * this behavior will be cancelled while running if the robot is disabled, and will not be able - * to be scheduled while disabled. - */ - CancelWhileDisabled, - /** - * Behavior that will allow a command to run while the robot is disabled. This allows safe - * commands - commands that do not try to move actuators - to still be able to run do perform - * tasks like updating data buffers or resetting sensors and odometry. Note that even if a - * command that does try to move actuators has this behavior, it will be unable to effect - * any movement due to the inbuilt safety mechanisms in the roboRIO and vendor hardware. - */ - RunWhileDisabled, - } - - /** - * The behavior of this command when the robot is disabled. Defaults to {@link - * RobotDisabledBehavior#CancelWhileDisabled}. - * - * @return the command's behavior during robot disable. - */ - default RobotDisabledBehavior robotDisabledBehavior() { - return RobotDisabledBehavior.CancelWhileDisabled; - } - /** * Checks if this command has a lower {@link #priority() priority} than another command. * diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 2bea35a939e..1880a0d59b6 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -8,6 +8,7 @@ import java.util.Arrays; import java.util.Collection; +import java.util.Collections; import java.util.HashSet; import java.util.List; import java.util.Objects; @@ -23,8 +24,6 @@ public class CommandBuilder { private Runnable onCancel = () -> {}; private String name; private int priority = Command.DEFAULT_PRIORITY; - private Command.RobotDisabledBehavior disabledBehavior = - Command.RobotDisabledBehavior.CancelWhileDisabled; /** * Adds a resource as a requirement for the command. @@ -120,31 +119,6 @@ public CommandBuilder withPriority(int priority) { return this; } - /** - * Marks the command as being able to run while the robot is disabled. - * - * @return The builder object, for chaining - * @see Command#robotDisabledBehavior() - */ - public CommandBuilder ignoringDisable() { - return withDisabledBehavior(Command.RobotDisabledBehavior.RunWhileDisabled); - } - - /** - * Gives the command the given behavior when the robot is disabled. - * - * @param behavior The behavior when the robot is disabled - * @return The builder object, for chaining - * @see Command#robotDisabledBehavior() - * @see #ignoringDisable() - */ - public CommandBuilder withDisabledBehavior(Command.RobotDisabledBehavior behavior) { - requireNonNullParam(behavior, "behavior", "CommandBuilder.withDisabledBehavior"); - - this.disabledBehavior = behavior; - return this; - } - /** * Sets the code that the command will execute when it's being run by the scheduler. * @@ -210,14 +184,9 @@ public int priority() { return priority; } - @Override - public RobotDisabledBehavior robotDisabledBehavior() { - return disabledBehavior; - } - @Override public String toString() { - return name(); + return "Command name=" + name() + " priority=" + priority; } }; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index e0577725c32..832b342cfec 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -50,11 +50,6 @@ public String toString() { return name(); } - @Override - public RobotDisabledBehavior robotDisabledBehavior() { - return RobotDisabledBehavior.RunWhileDisabled; - } - @Override public boolean equals(Object obj) { return obj instanceof IdleCommand other && Objects.equals(this.resource, other.resource); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 9b2ccd783f5..c59a22cecce 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -23,7 +23,6 @@ public class ParallelGroup implements Command { private final Set requirements = new HashSet<>(); private final String name; private final int priority; - private RobotDisabledBehavior disabledBehavior; /** * Creates a new parallel group. @@ -79,14 +78,6 @@ public ParallelGroup( this.priority = allCommands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); - - this.disabledBehavior = RobotDisabledBehavior.RunWhileDisabled; - for (Command command : allCommands) { - if (command.robotDisabledBehavior() == RobotDisabledBehavior.CancelWhileDisabled) { - this.disabledBehavior = RobotDisabledBehavior.CancelWhileDisabled; - break; - } - } } /** @@ -140,11 +131,6 @@ public int priority() { return priority; } - @Override - public RobotDisabledBehavior robotDisabledBehavior() { - return disabledBehavior; - } - @Override public String toString() { return "ParallelGroup[name=" + name + "]"; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 82cdf143f0b..f04d6dfdbe2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -24,7 +24,6 @@ public class Sequence implements Command { private final List commands = new ArrayList<>(); private final Set requirements = new HashSet<>(); private final int priority; - private RobotDisabledBehavior robotDisabledBehavior; /** * Creates a new command sequence. @@ -42,14 +41,6 @@ public Sequence(String name, List commands) { this.priority = commands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); - - this.robotDisabledBehavior = RobotDisabledBehavior.RunWhileDisabled; - for (var command : commands) { - if (command.robotDisabledBehavior() == RobotDisabledBehavior.CancelWhileDisabled) { - this.robotDisabledBehavior = RobotDisabledBehavior.CancelWhileDisabled; - break; - } - } } @Override @@ -74,11 +65,6 @@ public int priority() { return priority; } - @Override - public RobotDisabledBehavior robotDisabledBehavior() { - return robotDisabledBehavior; - } - public static SequenceBuilder builder() { return new SequenceBuilder(); } From ddf147f40fe1b813ae75371878fc6bf54043e7fe Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:40:05 -0400 Subject: [PATCH 026/153] Add some documentation comments --- .../org/wpilib/commands3/Continuation.java | 2 +- .../java/org/wpilib/commands3/Coroutine.java | 3 +- .../wpilib/commands3/RequireableResource.java | 28 +++++++++++++++++++ .../java/org/wpilib/commands3/Scheduler.java | 1 + 4 files changed, 32 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index ee60fb23c57..e1b7ca06bb8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -157,7 +157,7 @@ public static void mountContinuation(Continuation continuation) { mountedContinuation.set(continuation); } } catch (Throwable t) { - // Anything thrown internally by Thread.setContinuation. + // `t` is anything thrown internally by Thread.setContinuation. // It only assigns to a field, no way to throw // However, if the invocation fails for some reason, we'll end up with an // IllegalStateException when attempting to run an unmounted continuation diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 9b5ef0cbbfd..758fec1a2b3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -65,7 +65,8 @@ public void park() { requireMounted(); while (true) { - Coroutine.this.yield(); + // 'this' is required because 'yield' is a semi-keyword and needs to be qualified + this.yield(); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index c18a35ddfc6..43b817d7e29 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -10,16 +10,31 @@ import java.util.List; import java.util.function.Consumer; +/** + * A resource that may be claimed by a command. A single claimable resource cannot be claimed by + * more than one running command at a time. + */ @SuppressWarnings("this-escape") public class RequireableResource implements Sendable { private final String name; private final Scheduler registeredScheduler; + /** + * Creates a new claimable resource, registered with the default scheduler instance. + * + * @param name The name of the resource. Cannot be null. + */ public RequireableResource(String name) { this(name, Scheduler.getInstance()); } + /** + * Creates a new claimable resource, registered with the given scheduler instance. + * + * @param name The name of the resource. Cannot be null. + * @param scheduler The registered scheduler. Cannot be null. + */ public RequireableResource(String name, Scheduler scheduler) { this.name = name; this.registeredScheduler = scheduler; @@ -54,10 +69,23 @@ public CommandBuilder run(Consumer command) { return new CommandBuilder().requiring(this).executing(command); } + /** + * Returns a command that idles this resource until another command claims it. The idle command + * has {@link Command#LOWEST_PRIORITY the lowest priority} and can be interrupted by any other + * command. + * + *

The default command for every claimable resource is an idle command.

+ * @return A new idle command. + */ public Command idle() { return new IdleCommand(this); } + /** + * Returns a command that idles this resource for the given duration of time. + * @param duration How long the resource should idle for. + * @return A new idle command. + */ public Command idle(Time duration) { return idle().withTimeout(duration); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 7eab94a335d..0525f00ed88 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -143,6 +143,7 @@ public void sideload(Consumer callback) { * @param callback the periodic function to run */ public void addPeriodic(Runnable callback) { + // TODO: Add a unit test for this sideload( (coroutine) -> { while (coroutine.yield()) { From 73ee346ab195ac5e0f1f733d89d493ef73725860 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:40:41 -0400 Subject: [PATCH 027/153] Rename `getScheduledCommands()` to `getQueuedCommands()` This is more descriptive --- commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java | 2 +- .../main/java/org/wpilib/commands3/proto/SchedulerProto.java | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 0525f00ed88..56e7e51f9c0 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -615,7 +615,7 @@ public EventLoop getDefaultEventLoop() { } /** For internal use. */ - public Collection getScheduledCommands() { + public Collection getQueuedCommands() { return onDeck.stream().map(CommandState::command).toList(); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java index eef015c392c..e61e136cb96 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java @@ -33,7 +33,7 @@ public Scheduler unpack(ProtobufScheduler msg) { public void pack(ProtobufScheduler msg, Scheduler scheduler) { var cp = new CommandProto(scheduler); - for (var command : scheduler.getScheduledCommands()) { + for (var command : scheduler.getQueuedCommands()) { ProtobufCommand commandMessage = cp.createMessage(); cp.pack(commandMessage, command); msg.addQueuedCommands(commandMessage); From 6b084c71f0d79112dc5e8af9de16c9193f6f9a98 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:40:58 -0400 Subject: [PATCH 028/153] Add explicit test for child commands not cancelling their parents --- .../org/wpilib/commands3/SchedulerTest.java | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index edf6fde528e..aee69c8818a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -437,6 +437,24 @@ void compositionsDoNotSelfCancel() { assertTrue(scheduler.isRunning(group)); } + @Test + void compositionsDoNotCancelParent() { + var res = new RequireableResource("The Resource", scheduler); + var group = res.run(co -> { + co.fork(res.run(Coroutine::park).named("First Child")); + co.fork(res.run(Coroutine::park).named("Second Child")); + co.park(); + }).named("Group"); + + scheduler.schedule(group); + scheduler.run(); + + assertEquals( + List.of("Group", "Second Child"), + scheduler.getRunningCommands().stream().map(Command::name).toList() + ); + } + @Test void compositionsDoNotNeedRequirements() { var r1 = new RequireableResource("R1", scheduler); From 5d9d6bb60e0742de5a478863105e8c41e7e77315 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:42:41 -0400 Subject: [PATCH 029/153] Remove automatic setting of default command in constructor --- .../src/main/java/org/wpilib/commands3/RequireableResource.java | 2 -- 1 file changed, 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 43b817d7e29..633368583e7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -14,7 +14,6 @@ * A resource that may be claimed by a command. A single claimable resource cannot be claimed by * more than one running command at a time. */ -@SuppressWarnings("this-escape") public class RequireableResource implements Sendable { private final String name; @@ -38,7 +37,6 @@ public RequireableResource(String name) { public RequireableResource(String name, Scheduler scheduler) { this.name = name; this.registeredScheduler = scheduler; - setDefaultCommand(idle()); } public String getName() { From b2cf1e2c9f314d2b67c4409929d4111857fd36d7 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:43:56 -0400 Subject: [PATCH 030/153] Remove Sendable from RequireableResource Doesn't do anything particularly useful, and Epilogue would ignore it 2027 will remove it anyway, no point in including it --- .../org/wpilib/commands3/RequireableResource.java | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 633368583e7..01b8ab75819 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -5,8 +5,6 @@ package org.wpilib.commands3; import edu.wpi.first.units.measure.Time; -import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableBuilder; import java.util.List; import java.util.function.Consumer; @@ -14,7 +12,7 @@ * A resource that may be claimed by a command. A single claimable resource cannot be claimed by * more than one running command at a time. */ -public class RequireableResource implements Sendable { +public class RequireableResource { private final String name; private final Scheduler registeredScheduler; @@ -96,13 +94,4 @@ public List getRunningCommands() { public String toString() { return name; } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("RequireableResource"); - builder.addStringArrayProperty( - "Current Commands", - () -> getRunningCommands().stream().map(Command::name).toArray(String[]::new), - null); - } } From a6e70438df8f310a5e4800b81b60d3534434d5d5 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 10 Jun 2025 18:45:04 -0400 Subject: [PATCH 031/153] Run wpiformat --- commandsv3/src/main/java/org/wpilib/commands3/Binding.java | 4 ++++ .../src/main/java/org/wpilib/commands3/BindingScope.java | 4 ++++ .../src/main/java/org/wpilib/commands3/BindingType.java | 4 ++++ .../main/java/org/wpilib/commands3/CommandTraceHelper.java | 5 ++++- 4 files changed, 16 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java index 8e5c40e648f..a2495de442b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java @@ -1,3 +1,7 @@ +// 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 org.wpilib.commands3; import edu.wpi.first.util.ErrorMessages; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java index d27ad85e70a..5f70c3aabe1 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java @@ -1,3 +1,7 @@ +// 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 org.wpilib.commands3; /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java index 28bd02510dc..7845cc0952f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java @@ -1,3 +1,7 @@ +// 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 org.wpilib.commands3; /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java index f3864a8f9d8..2e290469ef2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -1,3 +1,7 @@ +// 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 org.wpilib.commands3; import java.util.ArrayList; @@ -20,7 +24,6 @@ private CommandTraceHelper() { public static StackTraceElement[] modifyTrace( StackTraceElement[] commandExceptionTrace, StackTraceElement[] commandScheduleTrace) { - List frames = new ArrayList<>(); List filteredClasses = List.of( From f48061e86f10b7dc9c85236869e00cb830c673c2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 13:19:06 -0400 Subject: [PATCH 032/153] Rename Scheduler.getInstance() to Scheduler.getDefault() --- .../wpilib/commands3/RequireableResource.java | 2 +- .../java/org/wpilib/commands3/Scheduler.java | 2 +- .../java/org/wpilib/commands3/Trigger.java | 2 +- .../commands3/button/CommandGenericHID.java | 36 +++++++++---------- .../commands3/button/CommandJoystick.java | 4 +-- .../button/CommandPS4Controller.java | 28 +++++++-------- .../button/CommandPS5Controller.java | 28 +++++++-------- .../button/CommandStadiaController.java | 30 ++++++++-------- .../button/CommandXboxController.java | 24 ++++++------- 9 files changed, 78 insertions(+), 78 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 01b8ab75819..149d2074b5e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -23,7 +23,7 @@ public class RequireableResource { * @param name The name of the resource. Cannot be null. */ public RequireableResource(String name) { - this(name, Scheduler.getInstance()); + this(name, Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 56e7e51f9c0..dcff68a6db4 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -63,7 +63,7 @@ public class Scheduler implements ProtobufSerializable { * * @return the default scheduler instance. */ - public static Scheduler getInstance() { + public static Scheduler getDefault() { return defaultScheduler; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 2e6ae8506b0..4a07e006987 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -62,7 +62,7 @@ public Trigger(Scheduler scheduler, BooleanSupplier condition) { * @param condition the condition represented by this trigger */ public Trigger(BooleanSupplier condition) { - this(Scheduler.getInstance(), condition); + this(Scheduler.getDefault(), condition); } // For internal use diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 79a0482c601..f05fa5a80f5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -39,11 +39,11 @@ public GenericHID getHID() { * * @param button the button index * @return an event instance representing the button's digital signal attached to the {@link - * Scheduler#getInstance() default scheduler button scheduler}. + * Scheduler#getDefault() default scheduler button scheduler}. * @see #button(int, Scheduler) */ public Trigger button(int button) { - return this.button(button, Scheduler.getInstance()); + return this.button(button, Scheduler.getDefault()); } /** @@ -60,7 +60,7 @@ public Trigger button(int button, Scheduler scheduler) { /** * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, - * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. * *

The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, * upper-left is 315). @@ -69,7 +69,7 @@ public Trigger button(int button, Scheduler scheduler) { * @return a Trigger instance based around this angle of a POV on the HID. */ public Trigger pov(int angle) { - return pov(0, angle, Scheduler.getInstance()); + return pov(0, angle, Scheduler.getDefault()); } /** @@ -81,7 +81,7 @@ public Trigger pov(int angle) { * @param pov index of the POV to read (starting at 0). Defaults to 0. * @param angle POV angle in degrees, or -1 for the center / not pressed. * @param scheduler the scheduler instance to attach the event to. Defaults to {@link - * Scheduler#getInstance() the default command scheduler button scheduler}. + * Scheduler#getDefault() the default command scheduler button scheduler}. * @return a Trigger instance based around this angle of a POV on the HID. */ public Trigger pov(int pov, int angle, Scheduler scheduler) { @@ -90,7 +90,7 @@ public Trigger pov(int pov, int angle, Scheduler scheduler) { /** * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV - * on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button * scheduler}. * * @return a Trigger instance based around the 0 degree angle of a POV on the HID. @@ -101,7 +101,7 @@ public Trigger povUp() { /** * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler + * 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler * button scheduler}. * * @return a Trigger instance based around the 45 degree angle of a POV on the HID. @@ -112,7 +112,7 @@ public Trigger povUpRight() { /** * Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button * scheduler}. * * @return a Trigger instance based around the 90 degree angle of a POV on the HID. @@ -123,7 +123,7 @@ public Trigger povRight() { /** * Constructs a Trigger instance based around the 135 degree angle (right down) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command * scheduler button scheduler}. * * @return a Trigger instance based around the 135 degree angle of a POV on the HID. @@ -134,7 +134,7 @@ public Trigger povDownRight() { /** * Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button * scheduler}. * * @return a Trigger instance based around the 180 degree angle of a POV on the HID. @@ -145,7 +145,7 @@ public Trigger povDown() { /** * Constructs a Trigger instance based around the 225 degree angle (down left) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command * scheduler button scheduler}. * * @return a Trigger instance based around the 225 degree angle of a POV on the HID. @@ -156,7 +156,7 @@ public Trigger povDownLeft() { /** * Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler button + * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button * scheduler}. * * @return a Trigger instance based around the 270 degree angle of a POV on the HID. @@ -167,7 +167,7 @@ public Trigger povLeft() { /** * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command scheduler + * 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler * button scheduler}. * * @return a Trigger instance based around the 315 degree angle of a POV on the HID. @@ -178,7 +178,7 @@ public Trigger povUpLeft() { /** * Constructs a Trigger instance based around the center (not pressed) position of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getInstance() the default command + * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command * scheduler button scheduler}. * * @return a Trigger instance based around the center position of a POV on the HID. @@ -189,7 +189,7 @@ public Trigger povCenter() { /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. * * @param axis The axis to read, starting at 0 * @param threshold The value below which this trigger should return true. @@ -197,7 +197,7 @@ public Trigger povCenter() { * threshold. */ public Trigger axisLessThan(int axis, double threshold) { - return axisLessThan(axis, threshold, Scheduler.getInstance()); + return axisLessThan(axis, threshold, Scheduler.getDefault()); } /** @@ -217,7 +217,7 @@ public Trigger axisLessThan(int axis, double threshold, Scheduler scheduler) { /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getInstance() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. * * @param axis The axis to read, starting at 0 * @param threshold The value above which this trigger should return true. @@ -225,7 +225,7 @@ public Trigger axisLessThan(int axis, double threshold, Scheduler scheduler) { * threshold. */ public Trigger axisGreaterThan(int axis, double threshold) { - return axisGreaterThan(axis, threshold, Scheduler.getInstance()); + return axisGreaterThan(axis, threshold, Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java index 358484fbe63..d3998e27581 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java @@ -44,7 +44,7 @@ public Joystick getHID() { * @see #trigger(Scheduler) */ public Trigger trigger() { - return trigger(Scheduler.getInstance()); + return trigger(Scheduler.getDefault()); } /** @@ -66,7 +66,7 @@ public Trigger trigger(Scheduler scheduler) { * @see #top(Scheduler) */ public Trigger top() { - return top(Scheduler.getInstance()); + return top(Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index ec75639f66a..2af81d35f31 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -44,7 +44,7 @@ public PS4Controller getHID() { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L2() { - return L2(Scheduler.getInstance()); + return L2(Scheduler.getDefault()); } /** @@ -65,7 +65,7 @@ public Trigger L2(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R2() { - return R2(Scheduler.getInstance()); + return R2(Scheduler.getDefault()); } /** @@ -86,7 +86,7 @@ public Trigger R2(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L1() { - return L1(Scheduler.getInstance()); + return L1(Scheduler.getDefault()); } /** @@ -107,7 +107,7 @@ public Trigger L1(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R1() { - return R1(Scheduler.getInstance()); + return R1(Scheduler.getDefault()); } /** @@ -128,7 +128,7 @@ public Trigger R1(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L3() { - return L3(Scheduler.getInstance()); + return L3(Scheduler.getDefault()); } /** @@ -149,7 +149,7 @@ public Trigger L3(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R3() { - return R3(Scheduler.getInstance()); + return R3(Scheduler.getDefault()); } /** @@ -170,7 +170,7 @@ public Trigger R3(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger square() { - return square(Scheduler.getInstance()); + return square(Scheduler.getDefault()); } /** @@ -191,7 +191,7 @@ public Trigger square(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger cross() { - return cross(Scheduler.getInstance()); + return cross(Scheduler.getDefault()); } /** @@ -212,7 +212,7 @@ public Trigger cross(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger triangle() { - return triangle(Scheduler.getInstance()); + return triangle(Scheduler.getDefault()); } /** @@ -233,7 +233,7 @@ public Trigger triangle(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger circle() { - return circle(Scheduler.getInstance()); + return circle(Scheduler.getDefault()); } /** @@ -254,7 +254,7 @@ public Trigger circle(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger share() { - return share(Scheduler.getInstance()); + return share(Scheduler.getDefault()); } /** @@ -275,7 +275,7 @@ public Trigger share(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger PS() { - return PS(Scheduler.getInstance()); + return PS(Scheduler.getDefault()); } /** @@ -296,7 +296,7 @@ public Trigger PS(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger options() { - return options(Scheduler.getInstance()); + return options(Scheduler.getDefault()); } /** @@ -317,7 +317,7 @@ public Trigger options(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger touchpad() { - return touchpad(Scheduler.getInstance()); + return touchpad(Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 9d14192b5fe..04f2ade7ea1 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -44,7 +44,7 @@ public PS5Controller getHID() { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L2() { - return L2(Scheduler.getInstance()); + return L2(Scheduler.getDefault()); } /** @@ -65,7 +65,7 @@ public Trigger L2(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R2() { - return R2(Scheduler.getInstance()); + return R2(Scheduler.getDefault()); } /** @@ -86,7 +86,7 @@ public Trigger R2(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L1() { - return L1(Scheduler.getInstance()); + return L1(Scheduler.getDefault()); } /** @@ -107,7 +107,7 @@ public Trigger L1(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R1() { - return R1(Scheduler.getInstance()); + return R1(Scheduler.getDefault()); } /** @@ -128,7 +128,7 @@ public Trigger R1(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger L3() { - return L3(Scheduler.getInstance()); + return L3(Scheduler.getDefault()); } /** @@ -149,7 +149,7 @@ public Trigger L3(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger R3() { - return R3(Scheduler.getInstance()); + return R3(Scheduler.getDefault()); } /** @@ -170,7 +170,7 @@ public Trigger R3(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger square() { - return square(Scheduler.getInstance()); + return square(Scheduler.getDefault()); } /** @@ -191,7 +191,7 @@ public Trigger square(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger cross() { - return cross(Scheduler.getInstance()); + return cross(Scheduler.getDefault()); } /** @@ -212,7 +212,7 @@ public Trigger cross(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger triangle() { - return triangle(Scheduler.getInstance()); + return triangle(Scheduler.getDefault()); } /** @@ -233,7 +233,7 @@ public Trigger triangle(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger circle() { - return circle(Scheduler.getInstance()); + return circle(Scheduler.getDefault()); } /** @@ -254,7 +254,7 @@ public Trigger circle(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger create() { - return create(Scheduler.getInstance()); + return create(Scheduler.getDefault()); } /** @@ -275,7 +275,7 @@ public Trigger create(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger PS() { - return PS(Scheduler.getInstance()); + return PS(Scheduler.getDefault()); } /** @@ -296,7 +296,7 @@ public Trigger PS(Scheduler scheduler) { * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger options() { - return options(Scheduler.getInstance()); + return options(Scheduler.getDefault()); } /** @@ -317,7 +317,7 @@ public Trigger options(Scheduler scheduler) { * Scheduler#getDefaultEventLoop() default scheduler button loop}. */ public Trigger touchpad() { - return touchpad(Scheduler.getInstance()); + return touchpad(Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java index b33fa11be50..a3ac578f5b8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -45,7 +45,7 @@ public StadiaController getHID() { * @see #leftBumper(EventLoop) */ public Trigger leftBumper() { - return leftBumper(Scheduler.getInstance()); + return leftBumper(Scheduler.getDefault()); } /** @@ -67,7 +67,7 @@ public Trigger leftBumper(Scheduler scheduler) { * @see #rightBumper(EventLoop) */ public Trigger rightBumper() { - return rightBumper(Scheduler.getInstance()); + return rightBumper(Scheduler.getDefault()); } /** @@ -89,7 +89,7 @@ public Trigger rightBumper(Scheduler scheduler) { * @see #leftStick(EventLoop) */ public Trigger leftStick() { - return leftStick(Scheduler.getInstance()); + return leftStick(Scheduler.getDefault()); } /** @@ -111,7 +111,7 @@ public Trigger leftStick(Scheduler scheduler) { * @see #rightStick(EventLoop) */ public Trigger rightStick() { - return rightStick(Scheduler.getInstance()); + return rightStick(Scheduler.getDefault()); } /** @@ -133,7 +133,7 @@ public Trigger rightStick(Scheduler scheduler) { * @see #rightTrigger(EventLoop) */ public Trigger rightTrigger() { - return rightTrigger(Scheduler.getInstance()); + return rightTrigger(Scheduler.getDefault()); } /** @@ -155,7 +155,7 @@ public Trigger rightTrigger(Scheduler scheduler) { * @see #leftTrigger(EventLoop) */ public Trigger leftTrigger() { - return leftTrigger(Scheduler.getInstance()); + return leftTrigger(Scheduler.getDefault()); } /** @@ -177,7 +177,7 @@ public Trigger leftTrigger(Scheduler scheduler) { * @see #a(EventLoop) */ public Trigger a() { - return a(Scheduler.getInstance()); + return a(Scheduler.getDefault()); } /** @@ -199,7 +199,7 @@ public Trigger a(Scheduler scheduler) { * @see #b(EventLoop) */ public Trigger b() { - return b(Scheduler.getInstance()); + return b(Scheduler.getDefault()); } /** @@ -221,7 +221,7 @@ public Trigger b(Scheduler scheduler) { * @see #x(EventLoop) */ public Trigger x() { - return x(Scheduler.getInstance()); + return x(Scheduler.getDefault()); } /** @@ -243,7 +243,7 @@ public Trigger x(Scheduler scheduler) { * @see #y(EventLoop) */ public Trigger y() { - return y(Scheduler.getInstance()); + return y(Scheduler.getDefault()); } /** @@ -265,7 +265,7 @@ public Trigger y(Scheduler scheduler) { * @see #ellipses(EventLoop) */ public Trigger ellipses() { - return ellipses(Scheduler.getInstance()); + return ellipses(Scheduler.getDefault()); } /** @@ -287,7 +287,7 @@ public Trigger ellipses(Scheduler scheduler) { * @see #stadia(EventLoop) */ public Trigger stadia() { - return stadia(Scheduler.getInstance()); + return stadia(Scheduler.getDefault()); } /** @@ -309,7 +309,7 @@ public Trigger stadia(Scheduler scheduler) { * @see #google(EventLoop) */ public Trigger google() { - return google(Scheduler.getInstance()); + return google(Scheduler.getDefault()); } /** @@ -331,7 +331,7 @@ public Trigger google(Scheduler scheduler) { * @see #frame(EventLoop) */ public Trigger frame() { - return frame(Scheduler.getInstance()); + return frame(Scheduler.getDefault()); } /** @@ -353,7 +353,7 @@ public Trigger frame(Scheduler scheduler) { * @see #hamburger(EventLoop) */ public Trigger hamburger() { - return hamburger(Scheduler.getInstance()); + return hamburger(Scheduler.getDefault()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java index b92f3e78001..0982cdfad0a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -45,7 +45,7 @@ public XboxController getHID() { * @see #leftBumper(Scheduler) */ public Trigger leftBumper() { - return leftBumper(Scheduler.getInstance()); + return leftBumper(Scheduler.getDefault()); } /** @@ -67,7 +67,7 @@ public Trigger leftBumper(Scheduler scheduler) { * @see #rightBumper(Scheduler) */ public Trigger rightBumper() { - return rightBumper(Scheduler.getInstance()); + return rightBumper(Scheduler.getDefault()); } /** @@ -89,7 +89,7 @@ public Trigger rightBumper(Scheduler scheduler) { * @see #leftStick(Scheduler) */ public Trigger leftStick() { - return leftStick(Scheduler.getInstance()); + return leftStick(Scheduler.getDefault()); } /** @@ -111,7 +111,7 @@ public Trigger leftStick(Scheduler scheduler) { * @see #rightStick(Scheduler) */ public Trigger rightStick() { - return rightStick(Scheduler.getInstance()); + return rightStick(Scheduler.getDefault()); } /** @@ -133,7 +133,7 @@ public Trigger rightStick(Scheduler scheduler) { * @see #a(Scheduler) */ public Trigger a() { - return a(Scheduler.getInstance()); + return a(Scheduler.getDefault()); } /** @@ -155,7 +155,7 @@ public Trigger a(Scheduler scheduler) { * @see #b(Scheduler) */ public Trigger b() { - return b(Scheduler.getInstance()); + return b(Scheduler.getDefault()); } /** @@ -177,7 +177,7 @@ public Trigger b(Scheduler scheduler) { * @see #x(Scheduler) */ public Trigger x() { - return x(Scheduler.getInstance()); + return x(Scheduler.getDefault()); } /** @@ -199,7 +199,7 @@ public Trigger x(Scheduler scheduler) { * @see #y(Scheduler) */ public Trigger y() { - return y(Scheduler.getInstance()); + return y(Scheduler.getDefault()); } /** @@ -221,7 +221,7 @@ public Trigger y(Scheduler scheduler) { * @see #start(Scheduler) */ public Trigger start() { - return start(Scheduler.getInstance()); + return start(Scheduler.getDefault()); } /** @@ -243,7 +243,7 @@ public Trigger start(Scheduler scheduler) { * @see #back(Scheduler) */ public Trigger back() { - return back(Scheduler.getInstance()); + return back(Scheduler.getDefault()); } /** @@ -282,7 +282,7 @@ public Trigger leftTrigger(double threshold, Scheduler scheduler) { * loop}. */ public Trigger leftTrigger(double threshold) { - return leftTrigger(threshold, Scheduler.getInstance()); + return leftTrigger(threshold, Scheduler.getDefault()); } /** @@ -321,7 +321,7 @@ public Trigger rightTrigger(double threshold, Scheduler scheduler) { * loop}. */ public Trigger rightTrigger(double threshold) { - return rightTrigger(threshold, Scheduler.getInstance()); + return rightTrigger(threshold, Scheduler.getDefault()); } /** From 52405015d7198dc1c21e91c816625a1988403bad Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 13:23:38 -0400 Subject: [PATCH 033/153] Remove requirement for default commands to have low priorities --- .../src/main/java/org/wpilib/commands3/Scheduler.java | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index dcff68a6db4..2ea82046a41 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -70,9 +70,8 @@ public static Scheduler getDefault() { public Scheduler() {} /** - * Sets the default command for a resource. The command must require the resource, and cannot - * require any others. Default commands must have a lower priority than {@link - * Command#DEFAULT_PRIORITY} to function properly. + * Sets the default command for a resource. The command must require that resource, and cannot + * require any other resources. * * @param resource the resource for which to set the default command * @param defaultCommand the default command to execute on the resource @@ -89,10 +88,6 @@ public void scheduleAsDefaultCommand(RequireableResource resource, Command defau "A resource's default command cannot require other resources"); } - if (defaultCommand.priority() >= Command.DEFAULT_PRIORITY) { - throw new IllegalArgumentException("Default commands must be low priority"); - } - defaultCommands.put(resource, defaultCommand); schedule(defaultCommand); } From dd2b5652058ba04a816037b3c0463e5227c1fd08 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:09:49 -0400 Subject: [PATCH 034/153] Add until and asLongAs to CommandBuilder Allows end conditions to be specified without needing to manually go through parallel group construction --- .../org/wpilib/commands3/CommandBuilder.java | 34 +++++++++++++++++-- 1 file changed, 32 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 1880a0d59b6..7fbb6f64294 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -8,11 +8,11 @@ import java.util.Arrays; import java.util.Collection; -import java.util.Collections; import java.util.HashSet; import java.util.List; import java.util.Objects; import java.util.Set; +import java.util.function.BooleanSupplier; import java.util.function.Consumer; /** @@ -24,6 +24,7 @@ public class CommandBuilder { private Runnable onCancel = () -> {}; private String name; private int priority = Command.DEFAULT_PRIORITY; + private BooleanSupplier endCondition = null; /** * Adds a resource as a requirement for the command. @@ -147,6 +148,26 @@ public CommandBuilder whenCanceled(Runnable onCancel) { return this; } + /** + * Makes the command run until some end condition is met, if it hasn't already finished by then + * on its own. + * @param endCondition The hard end condition for the command. + * @return The builder object, for chaining. + */ + public CommandBuilder until(BooleanSupplier endCondition) { + this.endCondition = endCondition; + return this; + } + + /** + * Makes the command run while some condition is true, ending when the condition becomes inactive. + * @param endCondition The command active condition. + * @return The builder object, for chaining. + */ + public CommandBuilder asLongAs(BooleanSupplier active) { + return until(() -> !active.getAsBoolean()); + } + /** * Creates the command. * @@ -158,7 +179,7 @@ public Command make() { Objects.requireNonNull(name, "Name was not specified"); Objects.requireNonNull(impl, "Command logic was not specified"); - return new Command() { + var command = new Command() { @Override public void run(Coroutine coroutine) { impl.accept(coroutine); @@ -189,5 +210,14 @@ public String toString() { return "Command name=" + name() + " priority=" + priority; } }; + + if (endCondition == null) { + // No custom end condition, just return the raw command + return command; + } else { + // A custom end condition is implemented as a race group, since we cannot modify the command + // body to inject the end condition. + return new ParallelGroupBuilder().requiring(command).until(endCondition).named(name); + } } } From 498f95f3232b59d4a31b0901f15a3d3835180a7a Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:47:33 -0400 Subject: [PATCH 035/153] Rename `waitingFor` to `waitUntil` --- .../src/main/java/org/wpilib/commands3/Command.java | 11 +++++++++-- .../org/wpilib/commands3/ParallelGroupBuilder.java | 2 +- .../java/org/wpilib/commands3/SequenceBuilder.java | 2 +- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 078222dece2..8902f232cc2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -249,7 +249,7 @@ static SequenceBuilder sequence(Command... commands) { * @param condition The condition to wait for * @return A command builder */ - static CommandBuilder waitingFor(BooleanSupplier condition) { + static CommandBuilder waitUntil(BooleanSupplier condition) { return noRequirements( coroutine -> { while (!condition.getAsBoolean()) { @@ -258,9 +258,16 @@ static CommandBuilder waitingFor(BooleanSupplier condition) { }); } + /** + * Creates a command that runs this one and ends when the end condition is met (if this command + * has not already exited by then). + * + * @param endCondition The end condition to wait for. + * @return The waiting command + */ default ParallelGroupBuilder until(BooleanSupplier endCondition) { return ParallelGroup.builder() - .optional(this, Command.waitingFor(endCondition).named("Until Condition")); + .optional(this, Command.waitUntil(endCondition).named("Until Condition")); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 58f563186ca..4fa64b7bfb0 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -100,7 +100,7 @@ public ParallelGroup named(String name) { // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(group, Command.waitingFor(endCondition).named("Until Condition")) + .optional(group, Command.waitUntil(endCondition).named("Until Condition")) .named(name); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index 7bff4d5fc56..8e48d50aba3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -62,7 +62,7 @@ public Command named(String name) { // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(seq, Command.waitingFor(endCondition).named("Until Condition")) + .optional(seq, Command.waitUntil(endCondition).named("Until Condition")) .named(name); } From 8b968cabf0cbd227688250094b2aed0553615c61 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:48:33 -0400 Subject: [PATCH 036/153] Add Coroutine.waitUntil --- .../main/java/org/wpilib/commands3/Coroutine.java | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 758fec1a2b3..37117587c08 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -7,6 +7,7 @@ import edu.wpi.first.units.measure.Time; import java.util.Arrays; import java.util.Collection; +import java.util.function.BooleanSupplier; import java.util.function.Consumer; import java.util.stream.Collectors; @@ -251,6 +252,18 @@ public void wait(Time duration) { await(new WaitCommand(duration)); } + /** + * Yields until a condition is met. + * @param condition The condition to wait for + */ + public void waitUntil(BooleanSupplier condition) { + requireMounted(); + + while (!condition.getAsBoolean()) { + this.yield(); + } + } + /** * Advanced users only: this permits access to the backing command scheduler to run custom logic * not provided by the standard coroutine methods. Any commands manually scheduled through this From 8f3d4cb855d3dca73e157c9d718bde4ef9c263e5 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:52:42 -0400 Subject: [PATCH 037/153] Add RequireableResource.runRepeatedly and add docs for run --- .../wpilib/commands3/RequireableResource.java | 27 +++++++++++++++++-- 1 file changed, 25 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 149d2074b5e..8f77b3f5276 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -61,8 +61,31 @@ public Command getDefaultCommand() { return registeredScheduler.getDefaultCommandFor(this); } - public CommandBuilder run(Consumer command) { - return new CommandBuilder().requiring(this).executing(command); + /** + * Starts building a command that requires this resource. + * + * @param commandBody The main function body of the command. + * @return The command builder, for further configuration. + */ + public CommandBuilder run(Consumer commandBody) { + return new CommandBuilder().requiring(this).executing(commandBody); + } + + /** + * Starts building a command that requires this resource. The given function will be called + * repeatedly in an infinite loop. Useful for building commands that don't need state or multiple + * stages of logic. + * + * @param loopBody The body of the infinite loop. + * @return The command builder, for further configuration. + */ + public CommandBuilder runRepeatedly(Runnable loopBody) { + return run(coroutine -> { + while (true) { + loopBody.run(); + coroutine.yield(); + } + }); } /** From da191b7da877cc4d9ba9e3c8755150b39df9131b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:53:40 -0400 Subject: [PATCH 038/153] Make RequireableResource set idle default commands in constructor Mostly so that there'll always be a command running for a resource if users don't set a default --- .../org/wpilib/commands3/RequireableResource.java | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 8f77b3f5276..fe7761d638a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -17,6 +17,13 @@ public class RequireableResource { private final Scheduler registeredScheduler; + @SuppressWarnings("this-escape") + public RequireableResource() { + this.name = getClass().getSimpleName(); + this.registeredScheduler = Scheduler.getDefault(); + setDefaultCommand(idle()); + } + /** * Creates a new claimable resource, registered with the default scheduler instance. * @@ -32,9 +39,11 @@ public RequireableResource(String name) { * @param name The name of the resource. Cannot be null. * @param scheduler The registered scheduler. Cannot be null. */ + @SuppressWarnings("this-escape") public RequireableResource(String name, Scheduler scheduler) { this.name = name; this.registeredScheduler = scheduler; + setDefaultCommand(idle()); } public String getName() { @@ -57,6 +66,12 @@ public void setDefaultCommand(Command defaultCommand) { registeredScheduler.scheduleAsDefaultCommand(this, defaultCommand); } + /** + * Gets the default command that was set by the latest call to + * {@link #setDefaultCommand(Command)}. + * + * @return The currently configured default command + */ public Command getDefaultCommand() { return registeredScheduler.getDefaultCommandFor(this); } From 50438be65704ea4f4550038850ea66604bdc8df0 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:57:22 -0400 Subject: [PATCH 039/153] Add ParallelGroupBuilder.alongWith --- .../org/wpilib/commands3/ParallelGroupBuilder.java | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 4fa64b7bfb0..a2050c513ea 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -46,6 +46,18 @@ public ParallelGroupBuilder requiring(Command... commands) { return this; } + /** + * Adds a command to the group. The command must complete for the group to exit. + * + * @param command The command to add to the group + * @return The builder object, for chaining + */ + // Note: this primarily exists so users can cleanly chain .alongWith calls to build a + // parallel group, eg `fooCommand().alongWith(barCommand()).alongWith(bazCommand())` + public ParallelGroupBuilder alongWith(Command command) { + return requiring(command); + } + /** * Forces the group to be a pure race, where the group will finish after the first command in * the group completes. All other commands in the group will be canceled. From 799b25b88d2985e70160d1b315f914f58a175739 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 14 Jun 2025 14:58:00 -0400 Subject: [PATCH 040/153] Make EventLoop-taking Trigger constructor public Since users may want to be able to run custom event loops other than the default one in the scheduler --- commandsv3/src/main/java/org/wpilib/commands3/Trigger.java | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 4a07e006987..79f6c66eb2c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -65,8 +65,7 @@ public Trigger(BooleanSupplier condition) { this(Scheduler.getDefault(), condition); } - // For internal use - private Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition) { + public Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition) { this.scheduler = scheduler; m_loop = loop; m_condition = condition; From bc5d72874341578eca44b40df00542bf2ada0028 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 15 Jun 2025 11:47:58 -0400 Subject: [PATCH 041/153] Simplify Command.waitUntil Delegate to Coroutine.waitUntil instead of reimplementing --- commandsv3/src/main/java/org/wpilib/commands3/Command.java | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 8902f232cc2..7f04f50bee2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -250,12 +250,7 @@ static SequenceBuilder sequence(Command... commands) { * @return A command builder */ static CommandBuilder waitUntil(BooleanSupplier condition) { - return noRequirements( - coroutine -> { - while (!condition.getAsBoolean()) { - coroutine.yield(); - } - }); + return noRequirements(coroutine -> coroutine.waitUntil(condition)); } /** From a5236bb69d3f024e3acc7392c33fd6eff75d0b93 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 15 Jun 2025 11:59:34 -0400 Subject: [PATCH 042/153] Emit events during scheduler actions For advanced users to do telemetry, particularly for one-shot commands --- .../java/org/wpilib/commands3/Scheduler.java | 56 +++++++- .../org/wpilib/commands3/SchedulerEvent.java | 129 ++++++++++++++++++ 2 files changed, 184 insertions(+), 1 deletion(-) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 2ea82046a41..cda4a5ca1eb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -7,6 +7,7 @@ import static edu.wpi.first.units.Units.Microseconds; import static edu.wpi.first.units.Units.Milliseconds; +import edu.wpi.first.util.ErrorMessages; import edu.wpi.first.util.protobuf.ProtobufSerializable; import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.TimedRobot; @@ -14,6 +15,7 @@ import java.util.ArrayList; import java.util.Collection; import java.util.Collections; +import java.util.Iterator; import java.util.LinkedHashMap; import java.util.LinkedHashSet; import java.util.List; @@ -54,9 +56,12 @@ public class Scheduler implements ProtobufSerializable { public static final SchedulerProto proto = new SchedulerProto(); private double lastRunTimeMs = -1; + private final Set> eventListeners = new LinkedHashSet<>(); + /** The default scheduler instance. */ private static final Scheduler defaultScheduler = new Scheduler(); + /** * Gets the default scheduler instance for use in a robot program. Some built in command types use * the default scheduler and will not work as expected if used on another scheduler instance. @@ -223,6 +228,8 @@ ScheduleResult schedule(Binding binding) { buildCoroutine(command), binding); + emitEvent(SchedulerEvent.scheduled(command)); + if (currentState() != null) { // Scheduling a child command while running. Start it immediately instead of waiting a full // cycle. This prevents issues with deeply nested command groups taking many scheduler cycles @@ -268,6 +275,7 @@ private void evictConflictingOnDeckCommands(Command command) { // We don't need to call removeOrphanedChildren here because it hasn't started yet, // meaning it hasn't had a chance to schedule any children iterator.remove(); + emitEvent(SchedulerEvent.interrupted(scheduledCommand, command)); } } } @@ -298,6 +306,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { // Cancel the root commands for (var conflictingState : conflictingRootStates) { + emitEvent(SchedulerEvent.interrupted(conflictingState.command(), incomingState.command())); cancel(conflictingState.command()); } } @@ -350,6 +359,7 @@ public void cancel(Command command) { // Only run the hook if the command was running. If it was on deck or not // even in the scheduler at the time, then there's nothing to do command.onCancel(); + emitEvent(SchedulerEvent.evicted(command)); } // Clean up any orphaned child commands; their lifespan must not exceed the parent's @@ -432,6 +442,7 @@ private void runCommand(CommandState state) { executingCommands.push(state); long startMicros = RobotController.getTime(); + emitEvent(SchedulerEvent.mounted(command)); coroutine.mount(); try { coroutine.runToYieldPoint(); @@ -439,6 +450,7 @@ private void runCommand(CommandState state) { // Intercept the exception, inject stack frames from the schedule site, and rethrow it var binding = state.binding(); e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); + emitEvent(SchedulerEvent.completedWithError(command, e)); throw e; } finally { long endMicros = RobotController.getTime(); @@ -461,8 +473,12 @@ private void runCommand(CommandState state) { if (coroutine.isDone()) { // Immediately check if the command has completed and remove any children commands. // This prevents child commands from being executed one extra time in the run() loop + emitEvent(SchedulerEvent.completed(command)); commandStates.remove(command); removeOrphanedChildren(command); + } else { + // Yielded + emitEvent(SchedulerEvent.yielded(command)); } } @@ -591,9 +607,16 @@ public List getRunningCommandsFor(RequireableResource resource) { */ public void cancelAll() { // Remove scheduled children of running commands - onDeck.removeIf(s -> commandStates.containsKey(s.parent())); + for (Iterator iterator = onDeck.iterator(); iterator.hasNext(); ) { + CommandState state = iterator.next(); + if (commandStates.containsKey(state.parent())) { + iterator.remove(); + emitEvent(SchedulerEvent.evicted(state.command())); + } + } // Finally, remove running commands + commandStates.forEach((command, _state) -> emitEvent(SchedulerEvent.evicted(command))); commandStates.clear(); } @@ -678,4 +701,35 @@ public int runId(Command command) { public double lastRuntimeMs() { return lastRunTimeMs; } + + /** + * Adds a listener to handle events that are emitted by the scheduler. Events are emitted when + * certain actions are taken by user code or by internal processing logic in the scheduler. + * Listeners should take care to be quick, simple, and not schedule or cancel commands, as that + * may cause inconsistent scheduler behavior or even cause a program crash. + * + *

Listeners are primarily expected to be for data logging and telemetry. In particular, a + * one-shot command (one that never calls {@link Coroutine#yield()}) will never appear in the + * standard protobuf telemetry because it is scheduled, runs, and finishes all in a single + * scheduler cycle. However, {@link SchedulerEvent.Scheduled},{@link SchedulerEvent.Mounted}, and + * {@link SchedulerEvent.Completed} events will be emitted corresponding to those actions, and + * user code can listen for and log such events. + * + * @param listener The listener to add. Cannot be null. + * @throws NullPointerException if given a null listener + */ + public void addEventListener(Consumer listener) { + ErrorMessages.requireNonNullParam(listener, "listener", "addEventListener"); + + eventListeners.add(listener); + } + + private void emitEvent(SchedulerEvent event) { + // TODO: Prevent listeners from interacting with the scheduler. + // Scheduling or cancelling commands while the scheduler is processing will probably cause + // bugs in user code or even a program crash. + for (var listener : eventListeners) { + listener.accept(event); + } + } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java new file mode 100644 index 00000000000..26c965c28c7 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -0,0 +1,129 @@ +// 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 org.wpilib.commands3; + +import edu.wpi.first.wpilibj.RobotController; +import java.util.function.Consumer; + +/** + * An event that occurs during scheduler processing. This can range from + * {@link Scheduled a command being scheduled} by a trigger or manual call to + * {@link Scheduler#schedule(Command)} to {@link Interrupted a command being interrupted by another}. + * Event listeners can be registered with a scheduler via + * {@link Scheduler#addEventListener(Consumer)}. All events have a timestamp that indicates when + * the event occurred. + */ +public sealed interface SchedulerEvent { + /** + * The timestamp for when the event occurred. Measured in microseconds since some arbitrary + * start time. + * + * @return The event timestamp. + * @see RobotController#getTime() + */ + long timestampMicros(); + + static SchedulerEvent scheduled(Command command) { + return new Scheduled(command, RobotController.getTime()); + } + + static SchedulerEvent mounted(Command command) { + return new Mounted(command, RobotController.getTime()); + } + + static SchedulerEvent yielded(Command command) { + return new Yielded(command, RobotController.getTime()); + } + + static SchedulerEvent completed(Command command) { + return new Completed(command, RobotController.getTime()); + } + + static SchedulerEvent completedWithError(Command command, Throwable error) { + return new CompletedWithError(command, error, RobotController.getTime()); + } + + static SchedulerEvent evicted(Command command) { + return new Evicted(command, RobotController.getTime()); + } + + static SchedulerEvent interrupted(Command command, Command interrupter) { + return new Interrupted(command, interrupter, RobotController.getTime()); + } + + /** + * An event marking when a command is scheduled in {@link Scheduler#schedule(Command)}. + * + * @param command The command that was scheduled + * @param timestampMicros When the command was scheduled + */ + record Scheduled(Command command, long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command starts running. + * + * @param command The command that started + * @param timestampMicros When the command started + */ + record Mounted(Command command, long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command yielded control with {@link Coroutine#yield()}. + * + * @param command The command that yielded + * @param timestampMicros When the command yielded + */ + record Yielded(Command command, long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command completed naturally. + * + * @param command The command that completed + * @param timestampMicros When the command completed + */ + record Completed(Command command, long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command threw or encountered an unhanded exception. + * + * @param command The command that encountered the error + * @param error The unhandled error + * @param timestampMicros When the error occurred + */ + record CompletedWithError(Command command, + Throwable error, + long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command was evicted from the scheduler. Commands may be evicted when + * they've been scheduled, then another command requiring a shared resource is scheduled + * afterward; when cancelled via {@link Scheduler#cancel(Command)} or + * {@link Scheduler#cancelAll()}; or when they're running and interrupted by another command + * requiring a shared resource. + * + * @param command The command that was evicted + * @param timestampMicros When the command was evicted + */ + record Evicted(Command command, long timestampMicros) implements SchedulerEvent { + } + + /** + * An event marking when a command was interrupted by another. Typically followed by an + * {@link Evicted} event. + * + * @param command The command that was interrupted + * @param interrupter The interrupting command + * @param timestampMicros When the command was interrupted + */ + record Interrupted(Command command, + Command interrupter, + long timestampMicros) implements SchedulerEvent { + } +} From 36eac8bdaaa1313bc56ec6432101e5e3435bc7a3 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 15 Jun 2025 18:01:17 -0400 Subject: [PATCH 043/153] Linting Hungarian notation is a blight --- .../java/org/wpilib/commands3/Command.java | 14 +- .../org/wpilib/commands3/CommandBuilder.java | 50 +++--- .../org/wpilib/commands3/CommandState.java | 36 ++--- .../wpilib/commands3/CommandTraceHelper.java | 15 +- .../org/wpilib/commands3/Continuation.java | 33 ++-- .../wpilib/commands3/ContinuationScope.java | 10 +- .../java/org/wpilib/commands3/Coroutine.java | 67 ++++---- .../org/wpilib/commands3/IdleCommand.java | 14 +- .../org/wpilib/commands3/ParallelGroup.java | 36 ++--- .../commands3/ParallelGroupBuilder.java | 34 ++-- .../wpilib/commands3/RequireableResource.java | 29 ++-- .../java/org/wpilib/commands3/Scheduler.java | 151 +++++++++--------- .../org/wpilib/commands3/SchedulerEvent.java | 8 +- .../java/org/wpilib/commands3/Sequence.java | 46 ++++-- .../org/wpilib/commands3/SequenceBuilder.java | 18 +-- .../java/org/wpilib/commands3/Trigger.java | 59 ++++--- .../org/wpilib/commands3/WaitCommand.java | 8 +- .../commands3/button/InternalButton.java | 4 +- .../wpilib/commands3/proto/CommandProto.java | 16 +- .../org/wpilib/commands3/SchedulerTest.java | 8 +- 20 files changed, 352 insertions(+), 304 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 7f04f50bee2..ccb3c2d90ee 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -21,7 +21,7 @@ * command implementation must call {@link Coroutine#yield()} within any periodic * loop. Failure to do so may result in an unrecoverable infinite loop. * - * {@snippet lang = java: + *

{@snippet lang = java: * // A 2013-style class-based command definition * class ClassBasedCommand extends Command { * public ClassBasedCommand(Subsystem requiredSubsystem) { @@ -140,7 +140,9 @@ default int priority() { * @return true if this command has a lower priority than the other one, false otherwise */ default boolean isLowerPriorityThan(Command other) { - if (other == null) return false; + if (other == null) { + return false; + } return priority() < other.priority(); } @@ -269,9 +271,7 @@ default ParallelGroupBuilder until(BooleanSupplier endCondition) { * Starts creating a command sequence, starting from this command and then running the next one. * More commands can be added with the builder before naming and creating the sequence. * - *

- * - * {@snippet lang="java" : + *

{@snippet lang="java" : * Sequence aThenBThenC = * commandA() * .andThen(commandB()) @@ -290,9 +290,7 @@ default SequenceBuilder andThen(Command next) { * Starts creating a parallel command group, running this command alongside one or more other * commands. The group will exit once every command has finished. * - *

- * - * {@snippet lang="java" : + *

{@snippet lang="java" : * ParallelGroup abc = * commandA() * .alongWith(commandB(), commandC()) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 7fbb6f64294..0b6b51a56b7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -19,12 +19,12 @@ * A builder that allows for all functionality of a command to be configured prior to creating it. */ public class CommandBuilder { - private final Set requirements = new HashSet<>(); - private Consumer impl; - private Runnable onCancel = () -> {}; - private String name; - private int priority = Command.DEFAULT_PRIORITY; - private BooleanSupplier endCondition = null; + private final Set m_requirements = new HashSet<>(); + private Consumer m_impl; + private Runnable m_onCancel = () -> {}; + private String m_name; + private int m_priority = Command.DEFAULT_PRIORITY; + private BooleanSupplier m_endCondition = null; /** * Adds a resource as a requirement for the command. @@ -36,7 +36,7 @@ public class CommandBuilder { public CommandBuilder requiring(RequireableResource resource) { requireNonNullParam(resource, "resource", "CommandBuilder.requiring"); - requirements.add(resource); + m_requirements.add(resource); return this; } @@ -53,7 +53,7 @@ public CommandBuilder requiring(RequireableResource... resources) { requireNonNullParam(resources[i], "resources[" + i + "]", "CommandBuilder.requiring"); } - requirements.addAll(Arrays.asList(resources)); + m_requirements.addAll(Arrays.asList(resources)); return this; } @@ -77,7 +77,7 @@ public CommandBuilder requiring(Collection resources) { } } - requirements.addAll(resources); + m_requirements.addAll(resources); return this; } @@ -91,7 +91,7 @@ public CommandBuilder requiring(Collection resources) { public CommandBuilder withName(String name) { requireNonNullParam(name, "name", "CommandBuilder.withName"); - this.name = name; + m_name = name; return this; } @@ -116,7 +116,7 @@ public Command named(String name) { * @see Command#priority() */ public CommandBuilder withPriority(int priority) { - this.priority = priority; + m_priority = priority; return this; } @@ -130,7 +130,7 @@ public CommandBuilder withPriority(int priority) { public CommandBuilder executing(Consumer impl) { requireNonNullParam(impl, "impl", "CommandBuilder.executing"); - this.impl = impl; + m_impl = impl; return this; } @@ -144,7 +144,7 @@ public CommandBuilder executing(Consumer impl) { public CommandBuilder whenCanceled(Runnable onCancel) { requireNonNullParam(onCancel, "onCancel", "CommandBuilder.whenCanceled"); - this.onCancel = onCancel; + m_onCancel = onCancel; return this; } @@ -155,13 +155,13 @@ public CommandBuilder whenCanceled(Runnable onCancel) { * @return The builder object, for chaining. */ public CommandBuilder until(BooleanSupplier endCondition) { - this.endCondition = endCondition; + m_endCondition = endCondition; return this; } /** * Makes the command run while some condition is true, ending when the condition becomes inactive. - * @param endCondition The command active condition. + * @param active The command active condition. * @return The builder object, for chaining. */ public CommandBuilder asLongAs(BooleanSupplier active) { @@ -176,48 +176,48 @@ public CommandBuilder asLongAs(BooleanSupplier active) { * #executing(Consumer) implementation} were not configured before calling this method. */ public Command make() { - Objects.requireNonNull(name, "Name was not specified"); - Objects.requireNonNull(impl, "Command logic was not specified"); + Objects.requireNonNull(m_name, "Name was not specified"); + Objects.requireNonNull(m_impl, "Command logic was not specified"); var command = new Command() { @Override public void run(Coroutine coroutine) { - impl.accept(coroutine); + m_impl.accept(coroutine); } @Override public void onCancel() { - onCancel.run(); + m_onCancel.run(); } @Override public String name() { - return name; + return m_name; } @Override public Set requirements() { - return requirements; + return m_requirements; } @Override public int priority() { - return priority; + return m_priority; } @Override public String toString() { - return "Command name=" + name() + " priority=" + priority; + return m_name; } }; - if (endCondition == null) { + if (m_endCondition == null) { // No custom end condition, just return the raw command return command; } else { // A custom end condition is implemented as a race group, since we cannot modify the command // body to inject the end condition. - return new ParallelGroupBuilder().requiring(command).until(endCondition).named(name); + return new ParallelGroupBuilder().requiring(command).until(m_endCondition).named(m_name); } } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index d49dc371a87..7236636b8c7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -6,15 +6,17 @@ /** Represents the state of a command as it is executed by the scheduler. */ final class CommandState { - private final Command command; - private final Command parent; - private final Coroutine coroutine; - private final Binding binding; // may be null + private final Command m_command; + private final Command m_parent; + private final Coroutine m_coroutine; + private final Binding m_binding; private double lastRuntimeMs = -1; private double totalRuntimeMs = 0; private final int id = System.identityHashCode(this); /** + * Creates a new command state object. + * * @param command The command being tracked. * @param parent The parent command composition that scheduled the tracked command. Null if the * command was scheduled by a top level construct like trigger bindings or manually scheduled @@ -22,32 +24,30 @@ final class CommandState { * that invoked the schedule() call; in this manner, an ancestry tree can be built, where each * {@code CommandState} object references a parent node in the tree. * @param coroutine The coroutine to which the command is bound. - * @param scheduleFrames The stack frames for the schedule site; that is, the backtrace of the - * code that caused the command to be scheduled. These let us report better traces when - * commands encounter exceptions. + * @param binding The binding that caused the command to be scheduled. */ CommandState(Command command, Command parent, Coroutine coroutine, Binding binding) { - this.command = command; - this.parent = parent; - this.coroutine = coroutine; - this.binding = binding; // may be null + m_command = command; + m_parent = parent; + m_coroutine = coroutine; + m_binding = binding; } public Command command() { - return command; + return m_command; } public Command parent() { - return parent; + return m_parent; } public Coroutine coroutine() { - return coroutine; + return m_coroutine; } // may return null public Binding binding() { - return binding; + return m_binding; } /** @@ -87,13 +87,13 @@ public int hashCode() { public String toString() { return "CommandState[" + "command=" - + command + + m_command + ", " + "parent=" - + parent + + m_parent + ", " + "coroutine=" - + coroutine + + m_coroutine + ']'; } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java index 2e290469ef2..37d0f330bd9 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -52,14 +52,15 @@ public static StackTraceElement[] modifyTrace( // The first frame here should be the line of user code that bound the command to a trigger. Stream.of(commandScheduleTrace) .dropWhile(frame -> { - return frame.getClassName().equals(Trigger.class.getName()) || - (frame.getClassName().equals(Scheduler.class.getName()) - && frame.getMethodName().equals("schedule")); - }) - .filter(frame -> { - return !filteredClasses.contains(frame.getClassName()); + boolean inTriggerInternals = frame.getClassName().equals(Trigger.class.getName()); + boolean isScheduleCall = + frame.getClassName().equals(Scheduler.class.getName()) + && frame.getMethodName().equals("schedule"); + + return inTriggerInternals || isScheduleCall; }) - .forEach(frames::add); + .filter(frame -> !filteredClasses.contains(frame.getClassName())) + .forEach(frames::add); break; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index e1b7ca06bb8..bc51996d11f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -12,7 +12,7 @@ /** A wrapper around the JDK internal Continuation class. */ public final class Continuation { // The underlying jdk.internal.vm.Continuation object - final Object continuation; + final Object m_continuation; static final Class jdk_internal_vm_Continuation; private static final MethodHandle CONSTRUCTOR; @@ -76,7 +76,7 @@ public final class Continuation { } } - private final ContinuationScope scope; + private final ContinuationScope m_scope; /** * Constructs a continuation. @@ -86,23 +86,22 @@ public final class Continuation { */ public Continuation(ContinuationScope scope, Runnable target) { try { - this.continuation = CONSTRUCTOR.invoke(scope.continuationScope, target); - this.scope = scope; + m_continuation = CONSTRUCTOR.invoke(scope.m_continuationScope, target); + m_scope = scope; } catch (Throwable t) { throw new RuntimeException(t); } } /** - * Suspends the current continuations up to the given scope. + * Suspends the current continuations up to this continuation's scope. * - * @param scope The {@link ContinuationScope} to suspend * @return {@code true} for success; {@code false} for failure - * @throws IllegalStateException if not currently in the given {@code scope}, + * @throws IllegalStateException if not currently in this continuation's scope */ - public static boolean yield(ContinuationScope scope) { + public boolean yield() { try { - return (boolean) YIELD.invoke(scope.continuationScope); + return (boolean) YIELD.invoke(m_scope.m_continuationScope); } catch (RuntimeException e) { throw e; } catch (Throwable t) { @@ -115,7 +114,7 @@ public static boolean yield(ContinuationScope scope) { */ public void run() { try { - RUN.invoke(continuation); + RUN.invoke(m_continuation); } catch (WrongMethodTypeException | ClassCastException e) { throw new IllegalStateException("Unable to run the underlying continuation!", e); } catch (RuntimeException e) { @@ -129,13 +128,13 @@ public void run() { } /** - * Tests whether this continuation is completed + * Tests whether this continuation is completed. * * @return whether this continuation is completed */ public boolean isDone() { try { - return (boolean) IS_DONE.invoke(continuation); + return (boolean) IS_DONE.invoke(m_continuation); } catch (Throwable t) { throw new RuntimeException(t); } @@ -153,7 +152,7 @@ public static void mountContinuation(Continuation continuation) { java_lang_thread_setContinuation.invoke(Thread.currentThread(), null); mountedContinuation.remove(); } else { - java_lang_thread_setContinuation.invoke(Thread.currentThread(), continuation.continuation); + java_lang_thread_setContinuation.invoke(Thread.currentThread(), continuation.m_continuation); mountedContinuation.set(continuation); } } catch (Throwable t) { @@ -176,15 +175,9 @@ public static Continuation getMountedContinuation() { @Override public String toString() { - return continuation.toString(); + return m_continuation.toString(); } - /** - * @see Continuation#yield(ContinuationScope) - */ - public boolean yield() { - return Continuation.yield(scope); - } boolean isMounted() { return this == getMountedContinuation(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index 3c8a6ba9994..46720ee4318 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -11,7 +11,7 @@ public final class ContinuationScope { // The underlying jdk.internal.vm.ContinuationScope object - final Object continuationScope; + final Object m_continuationScope; static final Class jdk_internal_vm_ContinuationScope; private static final MethodHandle CONSTRUCTOR; @@ -31,10 +31,14 @@ public final class ContinuationScope { } } + /** + * Constructs a new scope. + * @param name The scope's name + */ public ContinuationScope(String name) { Objects.requireNonNull(name); try { - this.continuationScope = CONSTRUCTOR.invoke(name); + m_continuationScope = CONSTRUCTOR.invoke(name); } catch (Throwable e) { throw new RuntimeException(e); } @@ -42,6 +46,6 @@ public ContinuationScope(String name) { @Override public String toString() { - return continuationScope.toString(); + return m_continuationScope.toString(); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 37117587c08..d59f86da7dd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -16,17 +16,20 @@ * commands to yield and compositions to run other commands. */ public final class Coroutine { - private final Scheduler scheduler; - private final Continuation backingContinuation; + private final Scheduler m_scheduler; + private final Continuation m_backingContinuation; + /** + * Creates a new coroutine. Package-private; only the scheduler should be creating these. + * + * @param scheduler The scheduler running the coroutine + * @param scope The continuation scope the coroutine's backing continuation runs in + * @param callback The callback for the continuation to execute when mounted. Often a command + * function's body. + */ Coroutine(Scheduler scheduler, ContinuationScope scope, Consumer callback) { - this.scheduler = scheduler; - this.backingContinuation = - new Continuation( - scope, - () -> { - callback.accept(this); - }); + m_scheduler = scheduler; + m_backingContinuation = new Continuation(scope, () -> callback.accept(this)); } /** @@ -39,15 +42,15 @@ public boolean yield() { requireMounted(); try { - return backingContinuation.yield(); + return m_backingContinuation.yield(); } catch (IllegalStateException e) { if (e.getMessage().equals("Pinned: MONITOR")) { // Yielding inside a synchronized block or method // Throw with an error message that's more helpful for our users throw new IllegalStateException( - "Coroutine.yield() cannot be called inside a synchronized block or method. " + - "Consider using a Lock instead of synchronized, " + - "or rewrite your code to avoid locks and mutexes altogether.", + "Coroutine.yield() cannot be called inside a synchronized block or method. " + + "Consider using a Lock instead of synchronized, " + + "or rewrite your code to avoid locks and mutexes altogether.", e ); } else { @@ -75,8 +78,8 @@ public void park() { * Forks off a command. It will run until its natural completion, the parent command exits, * or the parent command cancels it. The parent command will continue executing while the * forked command runs, and can resync with the forked command using {@link #await(Command)}. - *

- * {@snippet lang = java: + * + *

{@snippet lang = java: * Command example() { * return Command.noRequirements((coroutine) -> { * Command inner = ...; @@ -95,7 +98,7 @@ public void fork(Command... commands) { // Shorthand; this is handy for user-defined compositions for (var command : commands) { - scheduler.schedule(command); + m_scheduler.schedule(command); } } @@ -110,11 +113,11 @@ public void fork(Command... commands) { public void await(Command command) { requireMounted(); - if (!scheduler.isScheduledOrRunning(command)) { - scheduler.schedule(command); + if (!m_scheduler.isScheduledOrRunning(command)) { + m_scheduler.schedule(command); } - while (scheduler.isScheduledOrRunning(command)) { + while (m_scheduler.isScheduledOrRunning(command)) { // If the command is a one-shot, then the schedule call will completely execute the command. // There would be nothing to await this.yield(); @@ -135,12 +138,12 @@ public void awaitAll(Collection commands) { // Schedule anything that's not already queued or running for (var command : commands) { - if (!scheduler.isScheduledOrRunning(command)) { - scheduler.schedule(command); + if (!m_scheduler.isScheduledOrRunning(command)) { + m_scheduler.schedule(command); } } - while (commands.stream().anyMatch(scheduler::isScheduledOrRunning)) { + while (commands.stream().anyMatch(m_scheduler::isScheduledOrRunning)) { this.yield(); } @@ -172,16 +175,16 @@ public void awaitAny(Collection commands) { // Schedule anything that's not already queued or running for (var command : commands) { - if (!scheduler.isScheduledOrRunning(command)) { - scheduler.schedule(command); + if (!m_scheduler.isScheduledOrRunning(command)) { + m_scheduler.schedule(command); } } - while (commands.stream().allMatch(scheduler::isScheduledOrRunning)) { + while (commands.stream().allMatch(m_scheduler::isScheduledOrRunning)) { this.yield(); } - commands.forEach(scheduler::cancel); + commands.forEach(m_scheduler::cancel); } /** @@ -201,7 +204,7 @@ public void awaitAny(Command... commands) { * * @param commands The commands to validate * @throws IllegalArgumentException If at least one pair of commands is found in the input - * where both commands have at least one required resource in common + * where both commands have at least one required resource in common */ private static void validateNoConflicts(Collection commands) { for (var c1 : commands) { @@ -273,11 +276,11 @@ public void waitUntil(BooleanSupplier condition) { * @return the command scheduler backing this coroutine */ public Scheduler scheduler() { - return scheduler; + return m_scheduler; } private boolean isMounted() { - return backingContinuation.isMounted(); + return m_backingContinuation.isMounted(); } private void requireMounted() { @@ -297,14 +300,14 @@ private void requireMounted() { // These functions are not intended for team use. void runToYieldPoint() { - backingContinuation.run(); + m_backingContinuation.run(); } void mount() { - Continuation.mountContinuation(backingContinuation); + Continuation.mountContinuation(m_backingContinuation); } boolean isDone() { - return backingContinuation.isDone(); + return m_backingContinuation.isDone(); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index 832b342cfec..6eb78c3ac3a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -15,13 +15,15 @@ * interruption function like a normal command. */ public final class IdleCommand implements Command { - private final RequireableResource resource; + private final RequireableResource m_resource; /** + * Creates a new idle command. + * * @param resource the resource to idle. */ public IdleCommand(RequireableResource resource) { - this.resource = requireNonNullParam(resource, "resource", "IdleCommand"); + m_resource = requireNonNullParam(resource, "resource", "IdleCommand"); } @Override @@ -31,12 +33,12 @@ public void run(Coroutine coroutine) { @Override public Set requirements() { - return Set.of(resource); + return Set.of(m_resource); } @Override public String name() { - return resource.getName() + "[IDLE]"; + return m_resource.getName() + "[IDLE]"; } @Override @@ -52,11 +54,11 @@ public String toString() { @Override public boolean equals(Object obj) { - return obj instanceof IdleCommand other && Objects.equals(this.resource, other.resource); + return obj instanceof IdleCommand other && Objects.equals(this.m_resource, other.m_resource); } @Override public int hashCode() { - return Objects.hash(resource); + return Objects.hash(m_resource); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index c59a22cecce..90999c2fad3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -18,11 +18,11 @@ * has reached its completion condition will be cancelled. */ public class ParallelGroup implements Command { - private final Collection commands = new LinkedHashSet<>(); - private final Collection requiredCommands = new HashSet<>(); - private final Set requirements = new HashSet<>(); - private final String name; - private final int priority; + private final Collection m_commands = new LinkedHashSet<>(); + private final Collection m_requiredCommands = new HashSet<>(); + private final Set m_requirements = new HashSet<>(); + private final String m_name; + private final int m_priority; /** * Creates a new parallel group. @@ -68,15 +68,15 @@ public ParallelGroup( } } - this.name = name; - this.commands.addAll(allCommands); - this.requiredCommands.addAll(requiredCommands); + m_name = name; + this.m_commands.addAll(allCommands); + this.m_requiredCommands.addAll(requiredCommands); for (var command : allCommands) { - requirements.addAll(command.requirements()); + m_requirements.addAll(command.requirements()); } - this.priority = + m_priority = allCommands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); } @@ -103,37 +103,37 @@ public static ParallelGroupBuilder all(Command... commands) { @Override public void run(Coroutine coroutine) { - if (requiredCommands.isEmpty()) { + if (m_requiredCommands.isEmpty()) { // No command is explicitly required to complete // Schedule everything and wait for the first one to complete - coroutine.awaitAny(commands); + coroutine.awaitAny(m_commands); } else { // At least one command is required to complete // Schedule all the non-required commands (the scheduler will automatically cancel them // when this group completes), and await completion of all the required commands - commands.forEach(coroutine.scheduler()::schedule); - coroutine.awaitAll(requiredCommands); + m_commands.forEach(coroutine.scheduler()::schedule); + coroutine.awaitAll(m_requiredCommands); } } @Override public String name() { - return name; + return m_name; } @Override public Set requirements() { - return requirements; + return m_requirements; } @Override public int priority() { - return priority; + return m_priority; } @Override public String toString() { - return "ParallelGroup[name=" + name + "]"; + return "ParallelGroup[name=" + m_name + "]"; } public static ParallelGroupBuilder builder() { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index a2050c513ea..b9aa4d7a7af 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -17,9 +17,9 @@ * {@link #withAutomaticName()}. */ public class ParallelGroupBuilder { - private final Set commands = new LinkedHashSet<>(); - private final Set requiredCommands = new LinkedHashSet<>(); - private BooleanSupplier endCondition = null; + private final Set m_commands = new LinkedHashSet<>(); + private final Set m_requiredCommands = new LinkedHashSet<>(); + private BooleanSupplier m_endCondition = null; /** * Adds one or more optional commands to the group. They will not be required to complete for @@ -29,7 +29,7 @@ public class ParallelGroupBuilder { * @return The builder object, for chaining */ public ParallelGroupBuilder optional(Command... commands) { - this.commands.addAll(Arrays.asList(commands)); + this.m_commands.addAll(Arrays.asList(commands)); return this; } @@ -41,8 +41,8 @@ public ParallelGroupBuilder optional(Command... commands) { * @return The builder object, for chaining */ public ParallelGroupBuilder requiring(Command... commands) { - requiredCommands.addAll(Arrays.asList(commands)); - this.commands.addAll(requiredCommands); + m_requiredCommands.addAll(Arrays.asList(commands)); + this.m_commands.addAll(m_requiredCommands); return this; } @@ -65,7 +65,7 @@ public ParallelGroupBuilder alongWith(Command command) { * @return The builder object, for chaining */ public ParallelGroupBuilder racing() { - requiredCommands.clear(); + m_requiredCommands.clear(); return this; } @@ -76,8 +76,8 @@ public ParallelGroupBuilder racing() { * @return The builder object, for chaining */ public ParallelGroupBuilder requireAll() { - requiredCommands.clear(); - requiredCommands.addAll(commands); + m_requiredCommands.clear(); + m_requiredCommands.addAll(m_commands); return this; } @@ -91,7 +91,7 @@ public ParallelGroupBuilder requireAll() { * @return The builder object, for chaining */ public ParallelGroupBuilder until(BooleanSupplier condition) { - endCondition = condition; + m_endCondition = condition; return this; } @@ -104,15 +104,15 @@ public ParallelGroupBuilder until(BooleanSupplier condition) { * @return The built group */ public ParallelGroup named(String name) { - var group = new ParallelGroup(name, commands, requiredCommands); - if (endCondition == null) { + var group = new ParallelGroup(name, m_commands, m_requiredCommands); + if (m_endCondition == null) { // No custom end condition, return the group as is return group; } // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(group, Command.waitUntil(endCondition).named("Until Condition")) + .optional(group, Command.waitUntil(m_endCondition).named("Until Condition")) .named(name); } @@ -124,15 +124,15 @@ public ParallelGroup named(String name) { public ParallelGroup withAutomaticName() { // eg "(CommandA & CommandB & CommandC)" String required = - requiredCommands.stream().map(Command::name).collect(Collectors.joining(" & ", "(", ")")); + m_requiredCommands.stream().map(Command::name).collect(Collectors.joining(" & ", "(", ")")); - var optionalCommands = new LinkedHashSet<>(commands); - optionalCommands.removeAll(requiredCommands); + var optionalCommands = new LinkedHashSet<>(m_commands); + optionalCommands.removeAll(m_requiredCommands); // eg "(CommandA | CommandB | CommandC)" String optional = optionalCommands.stream().map(Command::name).collect(Collectors.joining(" | ", "(", ")")); - if (requiredCommands.isEmpty()) { + if (m_requiredCommands.isEmpty()) { // No required commands, pure race return named(optional); } else if (optionalCommands.isEmpty()) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index fe7761d638a..17ec140586a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -13,14 +13,19 @@ * more than one running command at a time. */ public class RequireableResource { - private final String name; + private final String m_name; - private final Scheduler registeredScheduler; + private final Scheduler m_registeredScheduler; + /** + * Creates a new requireable resource registered with the default scheduler instance and named + * using the name of the class. Intended to be used by subclasses to get sane defaults without + * needing to manually declare a constructor. + */ @SuppressWarnings("this-escape") - public RequireableResource() { - this.name = getClass().getSimpleName(); - this.registeredScheduler = Scheduler.getDefault(); + protected RequireableResource() { + m_name = getClass().getSimpleName(); + m_registeredScheduler = Scheduler.getDefault(); setDefaultCommand(idle()); } @@ -41,13 +46,13 @@ public RequireableResource(String name) { */ @SuppressWarnings("this-escape") public RequireableResource(String name, Scheduler scheduler) { - this.name = name; - this.registeredScheduler = scheduler; + m_name = name; + m_registeredScheduler = scheduler; setDefaultCommand(idle()); } public String getName() { - return name; + return m_name; } /** @@ -63,7 +68,7 @@ public String getName() { * @param defaultCommand the new default command */ public void setDefaultCommand(Command defaultCommand) { - registeredScheduler.scheduleAsDefaultCommand(this, defaultCommand); + m_registeredScheduler.scheduleAsDefaultCommand(this, defaultCommand); } /** @@ -73,7 +78,7 @@ public void setDefaultCommand(Command defaultCommand) { * @return The currently configured default command */ public Command getDefaultCommand() { - return registeredScheduler.getDefaultCommandFor(this); + return m_registeredScheduler.getDefaultCommandFor(this); } /** @@ -125,11 +130,11 @@ public Command idle(Time duration) { } public List getRunningCommands() { - return registeredScheduler.getRunningCommandsFor(this); + return m_registeredScheduler.getRunningCommandsFor(this); } @Override public String toString() { - return name; + return m_name; } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index cda4a5ca1eb..db7c54c4b58 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -28,38 +28,38 @@ /** Manages the lifecycles of {@link Coroutine}-based {@link Command Commands}. */ public class Scheduler implements ProtobufSerializable { - private final Map defaultCommands = new LinkedHashMap<>(); + private final Map m_defaultCommands = new LinkedHashMap<>(); /** The set of commands scheduled since the start of the previous run. */ - private final Set onDeck = new LinkedHashSet<>(); + private final Set m_onDeck = new LinkedHashSet<>(); /** The states of all running commands (does not include on deck commands). */ - private final Map commandStates = new LinkedHashMap<>(); + private final Map m_commandStates = new LinkedHashMap<>(); /** * The stack of currently executing commands. Child commands are pushed onto the stack and popped * when they complete. Use {@link #currentState()} and {@link #currentCommand()} to get the * currently executing command or its state. */ - private final Stack executingCommands = new Stack<>(); + private final Stack m_executingCommands = new Stack<>(); /** The periodic callbacks to run, outside of the command structure. */ - private final List periodicCallbacks = new ArrayList<>(); + private final List m_periodicCallbacks = new ArrayList<>(); /** Event loop for trigger bindings. */ - private final EventLoop eventLoop = new EventLoop(); + private final EventLoop m_eventLoop = new EventLoop(); /** The scope for continuations to yield to. */ - private final ContinuationScope scope = new ContinuationScope("coroutine commands"); + private final ContinuationScope m_scope = new ContinuationScope("coroutine commands"); // Telemetry public static final SchedulerProto proto = new SchedulerProto(); - private double lastRunTimeMs = -1; + private double m_lastRunTimeMs = -1; - private final Set> eventListeners = new LinkedHashSet<>(); + private final Set> m_eventListeners = new LinkedHashSet<>(); /** The default scheduler instance. */ - private static final Scheduler defaultScheduler = new Scheduler(); + private static final Scheduler s_defaultScheduler = new Scheduler(); /** @@ -69,7 +69,7 @@ public class Scheduler implements ProtobufSerializable { * @return the default scheduler instance. */ public static Scheduler getDefault() { - return defaultScheduler; + return s_defaultScheduler; } public Scheduler() {} @@ -93,7 +93,7 @@ public void scheduleAsDefaultCommand(RequireableResource resource, Command defau "A resource's default command cannot require other resources"); } - defaultCommands.put(resource, defaultCommand); + m_defaultCommands.put(resource, defaultCommand); schedule(defaultCommand); } @@ -104,7 +104,7 @@ public void scheduleAsDefaultCommand(RequireableResource resource, Command defau * @return The default command, or null if no default command was ever set */ public Command getDefaultCommandFor(RequireableResource resource) { - return defaultCommands.get(resource); + return m_defaultCommands.get(resource); } /** @@ -121,8 +121,8 @@ public Command getDefaultCommandFor(RequireableResource resource) { * @param callback the callback to sideload */ public void sideload(Consumer callback) { - var coroutine = new Coroutine(this, scope, callback); - periodicCallbacks.add(coroutine); + var coroutine = new Coroutine(this, m_scope, callback); + m_periodicCallbacks.add(coroutine); } /** @@ -145,7 +145,7 @@ public void sideload(Consumer callback) { public void addPeriodic(Runnable callback) { // TODO: Add a unit test for this sideload( - (coroutine) -> { + coroutine -> { while (coroutine.yield()) { callback.run(); } @@ -205,7 +205,7 @@ ScheduleResult schedule(Binding binding) { return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; } - for (var scheduledState : onDeck) { + for (var scheduledState : m_onDeck) { if (!command.conflictsWith(scheduledState.command())) { // No shared requirements, skip continue; @@ -235,13 +235,13 @@ ScheduleResult schedule(Binding binding) { // cycle. This prevents issues with deeply nested command groups taking many scheduler cycles // to start running the commands that actually /do/ things evictConflictingRunningCommands(state); - commandStates.put(command, state); + m_commandStates.put(command, state); runCommand(state); } else { // Scheduling outside a command, add it to the pending set. If it's not overridden by another // conflicting command being scheduled in the same scheduler loop, it'll be promoted and // start to run when #runCommands() is called - onDeck.add(state); + m_onDeck.add(state); } return ScheduleResult.SUCCESS; @@ -257,7 +257,7 @@ private boolean isSchedulable(Command command) { // Scheduling from outside a command, eg a trigger binding or manual schedule call // Check for conflicts with the commands that are already running - for (Command c : commandStates.keySet()) { + for (Command c : m_commandStates.keySet()) { if (c.conflictsWith(command) && command.isLowerPriorityThan(c)) { return false; } @@ -267,7 +267,7 @@ private boolean isSchedulable(Command command) { } private void evictConflictingOnDeckCommands(Command command) { - for (var iterator = onDeck.iterator(); iterator.hasNext(); ) { + for (var iterator = m_onDeck.iterator(); iterator.hasNext(); ) { var scheduledState = iterator.next(); var scheduledCommand = scheduledState.command(); if (scheduledCommand.conflictsWith(command)) { @@ -287,7 +287,7 @@ private void evictConflictingOnDeckCommands(Command command) { private void evictConflictingRunningCommands(CommandState incomingState) { // The set of root states with which the incoming state conflicts but does not inherit from Set conflictingRootStates = - commandStates.values().stream() + m_commandStates.values().stream() .filter(state -> incomingState.command().conflictsWith(state.command())) .filter(state -> !inheritsFrom(incomingState, state.command())) .map( @@ -298,7 +298,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { // incoming command CommandState root = state; while (root.parent() != null && root.parent() != incomingState.parent()) { - root = commandStates.get(root.parent()); + root = m_commandStates.get(root.parent()); } return root; }) @@ -323,7 +323,7 @@ private boolean inheritsFrom(CommandState state, Command ancestor) { // No parent, cannot inherit return false; } - if (!commandStates.containsKey(ancestor)) { + if (!m_commandStates.containsKey(ancestor)) { // The given ancestor isn't running return false; } @@ -332,7 +332,7 @@ private boolean inheritsFrom(CommandState state, Command ancestor) { return true; } // Check if the command's parent inherits from the given ancestor - return commandStates.values().stream() + return m_commandStates.values().stream() .filter(s -> state.parent() == s.command()) .anyMatch(s -> inheritsFrom(s, ancestor)); } @@ -352,8 +352,8 @@ public void cancel(Command command) { // Evict the command. The next call to run() will schedule the default command for all its // required resources, unless another command requiring those resources is scheduled between // calling cancel() and calling run() - commandStates.remove(command); - onDeck.removeIf(state -> state.command() == command); + m_commandStates.remove(command); + m_onDeck.removeIf(state -> state.command() == command); if (running) { // Only run the hook if the command was running. If it was on deck or not @@ -377,39 +377,39 @@ public void cancel(Command command) { * TimedRobot#robotPeriodic()} */ public void run() { - long startMicros = RobotController.getTime(); + final long startMicros = RobotController.getTime(); // Process triggers first; these tend to queue and cancel commands - eventLoop.poll(); + m_eventLoop.poll(); runPeriodicSideloads(); promoteScheduledCommands(); runCommands(); scheduleDefaultCommands(); - long endMicros = RobotController.getTime(); - lastRunTimeMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); + final long endMicros = RobotController.getTime(); + m_lastRunTimeMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); } private void promoteScheduledCommands() { // Clear any commands that conflict with the scheduled set - for (var queuedState : onDeck) { + for (var queuedState : m_onDeck) { evictConflictingRunningCommands(queuedState); } // Move any scheduled commands to the running set - for (var queuedState : onDeck) { - commandStates.put(queuedState.command(), queuedState); + for (var queuedState : m_onDeck) { + m_commandStates.put(queuedState.command(), queuedState); } // Clear the set of on-deck commands, // since we just put them all into the set of running commands - onDeck.clear(); + m_onDeck.clear(); } private void runPeriodicSideloads() { // Update periodic callbacks - for (Coroutine coroutine : periodicCallbacks) { + for (Coroutine coroutine : m_periodicCallbacks) { coroutine.mount(); try { coroutine.runToYieldPoint(); @@ -419,28 +419,28 @@ private void runPeriodicSideloads() { } // And remove any periodic callbacks that have completed - periodicCallbacks.removeIf(Coroutine::isDone); + m_periodicCallbacks.removeIf(Coroutine::isDone); } private void runCommands() { // Tick every command that hasn't been completed yet - for (var state : List.copyOf(commandStates.values())) { + for (var state : List.copyOf(m_commandStates.values())) { runCommand(state); } } private void runCommand(CommandState state) { final var command = state.command(); - var coroutine = state.coroutine(); + final var coroutine = state.coroutine(); - if (!commandStates.containsKey(command)) { + if (!m_commandStates.containsKey(command)) { // Probably canceled by an owning composition, do not run return; } var previousState = currentState(); - executingCommands.push(state); + m_executingCommands.push(state); long startMicros = RobotController.getTime(); emitEvent(SchedulerEvent.mounted(command)); coroutine.mount(); @@ -459,7 +459,7 @@ private void runCommand(CommandState state) { if (currentState() == state) { // Remove the command we just ran from the top of the stack - executingCommands.pop(); + m_executingCommands.pop(); } if (previousState != null) { @@ -474,7 +474,7 @@ private void runCommand(CommandState state) { // Immediately check if the command has completed and remove any children commands. // This prevents child commands from being executed one extra time in the run() loop emitEvent(SchedulerEvent.completed(command)); - commandStates.remove(command); + m_commandStates.remove(command); removeOrphanedChildren(command); } else { // Yielded @@ -488,12 +488,12 @@ private void runCommand(CommandState state) { * @return the currently executing command state */ private CommandState currentState() { - if (executingCommands.isEmpty()) { + if (m_executingCommands.isEmpty()) { // Avoid EmptyStackException return null; } - return executingCommands.peek(); + return m_executingCommands.peek(); } /** @@ -513,10 +513,10 @@ public Command currentCommand() { private void scheduleDefaultCommands() { // Schedule the default commands for every resource that doesn't currently have a running or // scheduled command. - defaultCommands.forEach( + m_defaultCommands.forEach( (resource, defaultCommand) -> { - if (commandStates.keySet().stream().noneMatch(c -> c.requires(resource)) - && onDeck.stream().noneMatch(c -> c.command().requires(resource))) { + if (m_commandStates.keySet().stream().noneMatch(c -> c.requires(resource)) + && m_onDeck.stream().noneMatch(c -> c.command().requires(resource))) { // Nothing currently running or scheduled // Schedule the resource's default command, if it has one if (defaultCommand != null) { @@ -533,7 +533,7 @@ private void scheduleDefaultCommands() { * @param parent the root command whose descendants to remove from the scheduler */ private void removeOrphanedChildren(Command parent) { - commandStates.entrySet().stream() + m_commandStates.entrySet().stream() .filter(e -> e.getValue().parent() == parent) .toList() // copy to an intermediate list to avoid concurrent modification .forEach(e -> cancel(e.getKey())); @@ -547,7 +547,7 @@ private void removeOrphanedChildren(Command parent) { * @return the binding coroutine */ private Coroutine buildCoroutine(Command command) { - return new Coroutine(this, scope, command::run); + return new Coroutine(this, m_scope, command::run); } /** @@ -557,7 +557,7 @@ private Coroutine buildCoroutine(Command command) { * @return true if the command is running, false if not */ public boolean isRunning(Command command) { - return commandStates.containsKey(command); + return m_commandStates.containsKey(command); } /** @@ -567,7 +567,7 @@ public boolean isRunning(Command command) { * @return true if the command is scheduled to run, false if not */ public boolean isScheduled(Command command) { - return onDeck.stream().anyMatch(state -> state.command() == command); + return m_onDeck.stream().anyMatch(state -> state.command() == command); } /** @@ -587,7 +587,7 @@ public boolean isScheduledOrRunning(Command command) { * @return the currently running commands */ public Collection getRunningCommands() { - return Collections.unmodifiableSet(commandStates.keySet()); + return Collections.unmodifiableSet(m_commandStates.keySet()); } /** @@ -598,7 +598,7 @@ public Collection getRunningCommands() { * @return the currently running commands that require the resource. */ public List getRunningCommandsFor(RequireableResource resource) { - return commandStates.keySet().stream().filter(command -> command.requires(resource)).toList(); + return m_commandStates.keySet().stream().filter(command -> command.requires(resource)).toList(); } /** @@ -607,17 +607,17 @@ public List getRunningCommandsFor(RequireableResource resource) { */ public void cancelAll() { // Remove scheduled children of running commands - for (Iterator iterator = onDeck.iterator(); iterator.hasNext(); ) { + for (Iterator iterator = m_onDeck.iterator(); iterator.hasNext(); ) { CommandState state = iterator.next(); - if (commandStates.containsKey(state.parent())) { + if (m_commandStates.containsKey(state.parent())) { iterator.remove(); emitEvent(SchedulerEvent.evicted(state.command())); } } // Finally, remove running commands - commandStates.forEach((command, _state) -> emitEvent(SchedulerEvent.evicted(command))); - commandStates.clear(); + m_commandStates.forEach((command, _state) -> emitEvent(SchedulerEvent.evicted(command))); + m_commandStates.clear(); } /** @@ -629,17 +629,17 @@ public void cancelAll() { * @return the default event loop. */ public EventLoop getDefaultEventLoop() { - return eventLoop; + return m_eventLoop; } /** For internal use. */ public Collection getQueuedCommands() { - return onDeck.stream().map(CommandState::command).toList(); + return m_onDeck.stream().map(CommandState::command).toList(); } /** For internal use. */ public Command getParentOf(Command command) { - var state = commandStates.get(command); + var state = m_commandStates.get(command); if (state == null) { return null; } @@ -653,9 +653,9 @@ public Command getParentOf(Command command) { * @param command The command to check * @return How long, in milliseconds, the command last took to execute. */ - public double lastRuntimeMs(Command command) { - if (commandStates.containsKey(command)) { - return commandStates.get(command).lastRuntimeMs(); + public double lastCommandRuntimeMs(Command command) { + if (m_commandStates.containsKey(command)) { + return m_commandStates.get(command).lastRuntimeMs(); } else { return -1; } @@ -669,21 +669,28 @@ public double lastRuntimeMs(Command command) { * @return How long, in milliseconds, the command has taken to execute in total */ public double totalRuntimeMs(Command command) { - if (commandStates.containsKey(command)) { - return commandStates.get(command).totalRuntimeMs(); + if (m_commandStates.containsKey(command)) { + return m_commandStates.get(command).totalRuntimeMs(); } else { // Not running; no data return -1; } } + /** + * Gets the unique run id for a scheduled or running command. If the command is not currently + * scheduled or running, this function returns {@code 0}. + * + * @param command The command to get the run ID for + * @return The run of the command + */ public int runId(Command command) { - if (commandStates.containsKey(command)) { - return commandStates.get(command).id(); + if (m_commandStates.containsKey(command)) { + return m_commandStates.get(command).id(); } // Check scheduled commands - for (var scheduled : onDeck) { + for (var scheduled : m_onDeck) { if (scheduled.command() == command) { return scheduled.id(); } @@ -699,7 +706,7 @@ public int runId(Command command) { * @return How long, in milliseconds, the scheduler last took to execute. */ public double lastRuntimeMs() { - return lastRunTimeMs; + return m_lastRunTimeMs; } /** @@ -721,14 +728,14 @@ public double lastRuntimeMs() { public void addEventListener(Consumer listener) { ErrorMessages.requireNonNullParam(listener, "listener", "addEventListener"); - eventListeners.add(listener); + m_eventListeners.add(listener); } private void emitEvent(SchedulerEvent event) { // TODO: Prevent listeners from interacting with the scheduler. // Scheduling or cancelling commands while the scheduler is processing will probably cause // bugs in user code or even a program crash. - for (var listener : eventListeners) { + for (var listener : m_eventListeners) { listener.accept(event); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index 26c965c28c7..c08837d301e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -10,10 +10,10 @@ /** * An event that occurs during scheduler processing. This can range from * {@link Scheduled a command being scheduled} by a trigger or manual call to - * {@link Scheduler#schedule(Command)} to {@link Interrupted a command being interrupted by another}. - * Event listeners can be registered with a scheduler via - * {@link Scheduler#addEventListener(Consumer)}. All events have a timestamp that indicates when - * the event occurred. + * {@link Scheduler#schedule(Command)} to + * {@link Interrupted a command being interrupted by another}. Event listeners can be registered + * with a scheduler via {@link Scheduler#addEventListener(Consumer)}. All events have a timestamp + * to indicate when the event occurred. */ public sealed interface SchedulerEvent { /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index f04d6dfdbe2..19e6a1d04df 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -20,55 +20,67 @@ * but not by a later one, will be uncommanded while that later command executes. */ public class Sequence implements Command { - private final String name; - private final List commands = new ArrayList<>(); - private final Set requirements = new HashSet<>(); - private final int priority; + private final String m_name; + private final List m_commands = new ArrayList<>(); + private final Set m_requirements = new HashSet<>(); + private final int m_priority; /** * Creates a new command sequence. * - * @param name the name of the sequence + * @param name the name of the sequence * @param commands the commands to execute within the sequence */ public Sequence(String name, List commands) { - this.name = name; - this.commands.addAll(commands); + m_name = name; + m_commands.addAll(commands); for (var command : commands) { - this.requirements.addAll(command.requirements()); + m_requirements.addAll(command.requirements()); } - this.priority = + m_priority = commands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); } @Override public void run(Coroutine coroutine) { - for (var command : commands) { + for (var command : m_commands) { coroutine.await(command); } } @Override public String name() { - return name; + return m_name; } @Override public Set requirements() { - return requirements; + return m_requirements; } @Override public int priority() { - return priority; + return m_priority; } + /** + * Creates a new sequence builder to start building a new sequence of commands. + * + * @return A new builder + */ public static SequenceBuilder builder() { return new SequenceBuilder(); } + /** + * Starts creating a sequence of the given commands. The commands will execute in the order in + * which they are passed to this function. + * + * @param commands The commands to execute in sequence + * @return A builder for further configuration + */ public static SequenceBuilder sequence(Command... commands) { var builder = new SequenceBuilder(); for (var command : commands) { @@ -77,6 +89,14 @@ public static SequenceBuilder sequence(Command... commands) { return builder; } + /** + * Creates a command that executes the given commands in sequence. The returned command will + * require all the resources required by every command in the sequence, and will have a priority + * equal to the highest priority of all the given commands. + * + * @param commands The commands to execute in sequence + * @return The sequence command + */ public static Command of(Command... commands) { return sequence(commands).withAutomaticName(); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index 8e48d50aba3..2ef460f3c13 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -17,8 +17,8 @@ * an automatically generated name using {@link #withAutomaticName()}. */ public class SequenceBuilder { - private final List steps = new ArrayList<>(); - private BooleanSupplier endCondition = null; + private final List m_steps = new ArrayList<>(); + private BooleanSupplier m_endCondition = null; /** * Adds a command to the sequence. @@ -29,7 +29,7 @@ public class SequenceBuilder { public SequenceBuilder andThen(Command next) { requireNonNullParam(next, "next", "Sequence.Builder.andThen"); - steps.add(next); + m_steps.add(next); return this; } @@ -39,11 +39,11 @@ public SequenceBuilder andThen(Command next) { * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end * condition added will be used and any previously configured condition will be overridden. * - * @param condition The end condition for the group + * @param endCondition The end condition for the group * @return The builder object, for chaining */ public SequenceBuilder until(BooleanSupplier endCondition) { - this.endCondition = endCondition; + m_endCondition = endCondition; return this; } @@ -54,15 +54,15 @@ public SequenceBuilder until(BooleanSupplier endCondition) { * @return The built command */ public Command named(String name) { - var seq = new Sequence(name, steps); - if (endCondition != null) { + var seq = new Sequence(name, m_steps); + if (m_endCondition != null) { // No custom end condition, return the group as is return seq; } // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(seq, Command.waitUntil(endCondition).named("Until Condition")) + .optional(seq, Command.waitUntil(m_endCondition).named("Until Condition")) .named(name); } @@ -73,6 +73,6 @@ public Command named(String name) { * @return The built command */ public Command withAutomaticName() { - return named(steps.stream().map(Command::name).collect(Collectors.joining(" -> "))); + return named(m_steps.stream().map(Command::name).collect(Collectors.joining(" -> "))); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 79f6c66eb2c..038a11ad20b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -28,7 +28,7 @@ public class Trigger implements BooleanSupplier { private final BooleanSupplier m_condition; private final EventLoop m_loop; - private final Scheduler scheduler; + private final Scheduler m_scheduler; private Signal m_previousSignal = null; private final Map> m_bindings = new EnumMap<>(BindingType.class); private final Runnable m_eventLoopCallback = this::poll; @@ -48,14 +48,22 @@ private enum Signal { LOW } + /** + * Creates a new trigger based on the given condition. Polled by the scheduler's + * {@link Scheduler#getDefaultEventLoop() default event loop}. + * + * @param scheduler The scheduler that should execute triggered commands. + * @param condition the condition represented by this trigger + */ public Trigger(Scheduler scheduler, BooleanSupplier condition) { - this.scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger"); - this.m_loop = scheduler.getDefaultEventLoop(); - this.m_condition = requireNonNullParam(condition, "condition", "Trigger"); + m_scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger"); + m_loop = scheduler.getDefaultEventLoop(); + m_condition = requireNonNullParam(condition, "condition", "Trigger"); } /** - * Creates a new trigger based on the given condition. + * Creates a new trigger based on the given condition. Triggered commands are executed by the + * {@link Scheduler#getDefault() default scheduler}. * *

Polled by the default scheduler button loop. * @@ -65,10 +73,17 @@ public Trigger(BooleanSupplier condition) { this(Scheduler.getDefault(), condition); } + /** + * Creates a new trigger based on the given condition. + * + * @param scheduler The scheduler that should execute triggered commands. + * @param loop The event loop to poll the trigger. + * @param condition the condition represented by this trigger + */ public Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition) { - this.scheduler = scheduler; - m_loop = loop; - m_condition = condition; + m_scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger"); + m_loop = requireNonNullParam(loop, "loop", "Trigger"); + m_condition = requireNonNullParam(condition, "condition", "Trigger"); } /** @@ -162,7 +177,7 @@ public boolean getAsBoolean() { */ public Trigger and(BooleanSupplier trigger) { return new Trigger( - scheduler, m_loop, () -> m_condition.getAsBoolean() && trigger.getAsBoolean()); + m_scheduler, m_loop, () -> m_condition.getAsBoolean() && trigger.getAsBoolean()); } /** @@ -173,7 +188,7 @@ public Trigger and(BooleanSupplier trigger) { */ public Trigger or(BooleanSupplier trigger) { return new Trigger( - scheduler, m_loop, () -> m_condition.getAsBoolean() || trigger.getAsBoolean()); + m_scheduler, m_loop, () -> m_condition.getAsBoolean() || trigger.getAsBoolean()); } /** @@ -183,7 +198,7 @@ public Trigger or(BooleanSupplier trigger) { * @return the negated trigger */ public Trigger negate() { - return new Trigger(scheduler, m_loop, () -> !m_condition.getAsBoolean()); + return new Trigger(m_scheduler, m_loop, () -> !m_condition.getAsBoolean()); } /** @@ -201,13 +216,13 @@ public Trigger debounce(Time duration) { * Creates a new debounced trigger from this trigger - it will become active when this trigger has * been active for longer than the specified period. * - * @param seconds The debounce period. + * @param duration The debounce period. * @param type The debounce type. * @return The debounced trigger. */ public Trigger debounce(Time duration, Debouncer.DebounceType type) { return new Trigger( - scheduler, + m_scheduler, m_loop, new BooleanSupplier() { final Debouncer m_debouncer = new Debouncer(duration.in(Seconds), type); @@ -263,9 +278,9 @@ private Signal signal() { * Removes bindings in inactive scopes. */ private void clearStaleBindings() { - m_bindings.forEach(((_bindingType, bindings) -> { + m_bindings.forEach((_bindingType, bindings) -> { bindings.removeIf(binding -> !binding.scope().active()); - })); + }); } /** @@ -275,7 +290,7 @@ private void clearStaleBindings() { */ private void scheduleBindings(BindingType bindingType) { m_bindings.getOrDefault(bindingType, List.of()) - .forEach(scheduler::schedule); + .forEach(m_scheduler::schedule); } /** @@ -285,7 +300,7 @@ private void scheduleBindings(BindingType bindingType) { */ private void cancelBindings(BindingType bindingType) { m_bindings.getOrDefault(bindingType, List.of()) - .forEach(binding -> scheduler.cancel(binding.command())); + .forEach(binding -> m_scheduler.cancel(binding.command())); } /** @@ -300,18 +315,18 @@ private void toggleBindings(BindingType bindingType) { .forEach( binding -> { var command = binding.command(); - if (scheduler.isScheduledOrRunning(command)) { - scheduler.cancel(command); + if (m_scheduler.isScheduledOrRunning(command)) { + m_scheduler.cancel(command); } else { - scheduler.schedule(binding); + m_scheduler.schedule(binding); } }); } private void addBinding(BindingType bindingType, Command command) { - BindingScope scope = switch (scheduler.currentCommand()) { + BindingScope scope = switch (m_scheduler.currentCommand()) { // A command is creating a binding - make it scoped to that specific command - case Command c -> BindingScope.forCommand(scheduler, c); + case Command c -> BindingScope.forCommand(m_scheduler, c); // Creating a binding outside a command - it's global in scope case null -> BindingScope.global(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java index d3277abd8bd..950c3526d36 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java @@ -13,24 +13,24 @@ /** A command with no requirements that merely waits for a specified duration of time to elapse. */ public class WaitCommand implements Command { - private final Time duration; + private final Time m_duration; public WaitCommand(Time duration) { - this.duration = requireNonNullParam(duration, "duration", "WaitCommand"); + m_duration = requireNonNullParam(duration, "duration", "WaitCommand"); } @Override public void run(Coroutine coroutine) { var timer = new Timer(); timer.start(); - while (!timer.hasElapsed(duration.in(Seconds))) { + while (!timer.hasElapsed(m_duration.in(Seconds))) { coroutine.yield(); } } @Override public String name() { - return "Wait " + duration.in(Seconds) + " Seconds"; + return "Wait " + m_duration.in(Seconds) + " Seconds"; } @Override diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java index 2378e1d054f..6bedec6d7fb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/InternalButton.java @@ -37,8 +37,8 @@ public InternalButton(boolean inverted) { */ private InternalButton(AtomicBoolean state, AtomicBoolean inverted) { super(() -> state.get() != inverted.get()); - this.m_pressed = state; - this.m_inverted = inverted; + m_pressed = state; + m_inverted = inverted; } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index 4b6f51c1f93..48246958a69 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -11,10 +11,10 @@ /** Protobuf serde for running commands. */ public class CommandProto implements Protobuf { - private final Scheduler scheduler; + private final Scheduler m_scheduler; public CommandProto(Scheduler scheduler) { - this.scheduler = scheduler; + m_scheduler = scheduler; } @Override @@ -40,9 +40,9 @@ public Command unpack(ProtobufCommand msg) { @Override public void pack(ProtobufCommand msg, Command command) { - msg.setId(scheduler.runId(command)); - if (scheduler.getParentOf(command) instanceof Command parent) { - msg.setParentId(scheduler.runId(parent)); + msg.setId(m_scheduler.runId(command)); + if (m_scheduler.getParentOf(command) instanceof Command parent) { + msg.setParentId(m_scheduler.runId(parent)); } msg.setName(command.name()); msg.setPriority(command.priority()); @@ -54,9 +54,9 @@ public void pack(ProtobufCommand msg, Command command) { msg.addRequirements(requirementMessage); } - if (scheduler.isRunning(command)) { - msg.setLastTimeMs(scheduler.lastRuntimeMs(command)); - msg.setTotalTimeMs(scheduler.totalRuntimeMs(command)); + if (m_scheduler.isRunning(command)) { + msg.setLastTimeMs(m_scheduler.lastCommandRuntimeMs(command)); + msg.setTotalTimeMs(m_scheduler.totalRuntimeMs(command)); } } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index aee69c8818a..db2f33c9c2b 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -713,22 +713,22 @@ void protobuf() { scheduler.runId(scheduledCommand2), // Running commands - scheduler.lastRuntimeMs(group), + scheduler.lastCommandRuntimeMs(group), scheduler.totalRuntimeMs(group), scheduler.runId(group), // id // top-level command, no parent ID - scheduler.lastRuntimeMs(c2Command), + scheduler.lastCommandRuntimeMs(c2Command), scheduler.totalRuntimeMs(c2Command), scheduler.runId(c2Command), // id scheduler.runId(group), // parent - scheduler.lastRuntimeMs(c3Command), + scheduler.lastCommandRuntimeMs(c3Command), scheduler.totalRuntimeMs(c3Command), scheduler.runId(c3Command), // id scheduler.runId(c2Command), // parent - scheduler.lastRuntimeMs(parkCommand), + scheduler.lastCommandRuntimeMs(parkCommand), scheduler.totalRuntimeMs(parkCommand), scheduler.runId(parkCommand), // id scheduler.runId(c3Command) // parent From f01d6d4414afed33746db939a889f16840790f15 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 08:54:51 -0400 Subject: [PATCH 044/153] Move generated protobuf classes to separate directory --- commandsv3/build.gradle | 1 + .../main/java/org/wpilib/commands3/proto/ProtobufCommand.java | 0 .../org/wpilib/commands3/proto/ProtobufRequireableResource.java | 0 .../main/java/org/wpilib/commands3/proto/ProtobufScheduler.java | 0 .../main/java/org/wpilib/commands3/proto/Scheduler.java | 0 commandsv3/src/main/proto/scheduler.proto | 2 +- 6 files changed, 2 insertions(+), 1 deletion(-) rename commandsv3/src/{ => generated}/main/java/org/wpilib/commands3/proto/ProtobufCommand.java (100%) rename commandsv3/src/{ => generated}/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java (100%) rename commandsv3/src/{ => generated}/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java (100%) rename commandsv3/src/{ => generated}/main/java/org/wpilib/commands3/proto/Scheduler.java (100%) diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index 7d3b685f84c..b067af5b1f0 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -27,6 +27,7 @@ dependencies { testImplementation 'org.mockito:mockito-core:4.1.0' } +sourceSets.main.java.srcDir "${projectDir}/src/generated/main/java" sourceSets.main.resources.srcDir "${projectDir}/src/main/proto" tasks.withType(Javadoc) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java similarity index 100% rename from commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufCommand.java rename to commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java similarity index 100% rename from commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java rename to commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java similarity index 100% rename from commandsv3/src/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java rename to commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java similarity index 100% rename from commandsv3/src/main/java/org/wpilib/commands3/proto/Scheduler.java rename to commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/scheduler.proto index c8ce963a7ff..6fb8193c3b7 100644 --- a/commandsv3/src/main/proto/scheduler.proto +++ b/commandsv3/src/main/proto/scheduler.proto @@ -7,7 +7,7 @@ option java_multiple_files = true; /* allwpilib $ protoc-quickbuf \ - --quickbuf_out=gen_descriptors=true:commandsv3/src/main/java \ + --quickbuf_out=gen_descriptors=true:commandsv3/src/generated/main/java \ commandsv3/src/main/proto/scheduler.proto */ From c71468915ed6e2446af8527bc3ccf9df8c084a60 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 09:23:32 -0400 Subject: [PATCH 045/153] Update joystick classes for parity and generate command controllers Revert trigger factories to accept an EventLoop again (instead of a scheduler), and instead register a scheduler instance with the controller object for configurability. Controllers default to use the default scheduler instance unless otherwise specified --- commandsv3/generate_hids.py | 68 +++ .../generate/main/java/commandhid.java.jinja | 141 ++++++ .../button/CommandPS4Controller.java | 417 +++++++++++++++++ .../button/CommandPS5Controller.java | 417 +++++++++++++++++ .../button/CommandStadiaController.java | 419 ++++++++++++++++++ .../button/CommandXboxController.java | 407 +++++++++++++++++ .../commands3/button/CommandGenericHID.java | 185 ++++++-- .../commands3/button/CommandJoystick.java | 60 ++- .../button/CommandPS4Controller.java | 389 ---------------- .../button/CommandPS5Controller.java | 389 ---------------- .../button/CommandStadiaController.java | 405 ----------------- .../button/CommandXboxController.java | 393 ---------------- 12 files changed, 2051 insertions(+), 1639 deletions(-) create mode 100755 commandsv3/generate_hids.py create mode 100644 commandsv3/src/generate/main/java/commandhid.java.jinja create mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java create mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java create mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java create mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java diff --git a/commandsv3/generate_hids.py b/commandsv3/generate_hids.py new file mode 100755 index 00000000000..f232556fad4 --- /dev/null +++ b/commandsv3/generate_hids.py @@ -0,0 +1,68 @@ +#!/usr/bin/env python3 + +# 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. + +import argparse +import json +from pathlib import Path + +from jinja2 import Environment, FileSystemLoader + + +def write_controller_file(output_dir: Path, controller_name: str, contents: str): + output_dir.mkdir(parents=True, exist_ok=True) + output_file = output_dir / controller_name + output_file.write_text(contents, encoding="utf-8", newline="\n") + + +def generate_hids(output_directory: Path, template_directory: Path, schema_file: Path): + with schema_file.open(encoding="utf-8") as f: + controllers = json.load(f) + + # Java files + java_subdirectory = "main/java/org/wpilib/commands3/button" + env = Environment( + loader=FileSystemLoader(template_directory / "main/java"), + autoescape=False, + keep_trailing_newline=True, + ) + root_path = output_directory / java_subdirectory + template = env.get_template("commandhid.java.jinja") + for controller in controllers: + controllerName = f"Command{controller['ConsoleName']}Controller.java" + output = template.render(controller) + write_controller_file(root_path, controllerName, output) + + +def main(): + script_path = Path(__file__).resolve() + dirname = script_path.parent + + parser = argparse.ArgumentParser() + parser.add_argument( + "--output_directory", + help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", + default=dirname / "src/generated", + type=Path, + ) + parser.add_argument( + "--template_root", + help="Optional. If set, will use this directory as the root for the jinja templates", + default=dirname / "src/generate", + type=Path, + ) + parser.add_argument( + "--schema_file", + help="Optional. If set, will use this file for the joystick schema", + default="wpilibj/src/generate/hids.json", + type=Path, + ) + args = parser.parse_args() + + generate_hids(args.output_directory, args.template_root, args.schema_file) + + +if __name__ == "__main__": + main() diff --git a/commandsv3/src/generate/main/java/commandhid.java.jinja b/commandsv3/src/generate/main/java/commandhid.java.jinja new file mode 100644 index 00000000000..7186c790e62 --- /dev/null +++ b/commandsv3/src/generate/main/java/commandhid.java.jinja @@ -0,0 +1,141 @@ +// 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. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +{% macro capitalize_first(string) -%} +{{ string[0]|capitalize + string[1:] }} +{%- endmacro %} +package org.wpilib.commands3.button; + +import edu.wpi.first.wpilibj.{{ ConsoleName }}Controller; +import edu.wpi.first.wpilibj.event.EventLoop; +import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; + +/** + * A version of {@link {{ ConsoleName }}Controller} with {@link Trigger} factories for command-based. + * + * @see {{ ConsoleName }}Controller + */ +@SuppressWarnings("MethodName") +public class Command{{ ConsoleName }}Controller extends CommandGenericHID { + private final {{ ConsoleName }}Controller m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public Command{{ ConsoleName }}Controller(int port) { + super(port); + m_hid = new {{ ConsoleName }}Controller(port); + } + + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public Command{{ ConsoleName }}Controller(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new {{ ConsoleName }}Controller(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public {{ ConsoleName }}Controller getHID() { + return m_hid; + } +{% for button in buttons %} + /** + * Constructs a Trigger instance around the {{ button.DocName|default(button.name) }} button's digital signal. + * + * @return a Trigger instance representing the {{ button.DocName|default(button.name) }} button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #{{ button.name }}(EventLoop) + */ + public Trigger {{ button.name }}() { + return {{ button.name }}(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the {{ button.DocName|default(button.name) }} button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the {{ button.DocName|default(button.name) }} button's digital signal attached + * to the given loop. + */ + public Trigger {{ button.name }}(EventLoop loop) { + return button({{ ConsoleName }}Controller.Button.k{{ capitalize_first(button.name) }}.value, loop); + } +{% endfor -%} +{% for trigger in triggers -%} +{% if trigger.UseThresholdMethods %} + /** + * Constructs a Trigger instance around the axis value of the {{ trigger.DocName }}. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @param loop the event loop instance to attach the Trigger to. + * @return a Trigger instance that is true when the {{ trigger.DocName }}'s axis exceeds the provided + * threshold, attached to the given event loop + */ + public Trigger {{ trigger.name }}(double threshold, EventLoop loop) { + return axisGreaterThan({{ ConsoleName }}Controller.Axis.k{{ capitalize_first(trigger.name) }}.value, threshold, loop); + } + + /** + * Constructs a Trigger instance around the axis value of the {{ trigger.DocName }}. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @return a Trigger instance that is true when the {{ trigger.DocName }}'s axis exceeds the provided + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler + * button loop}. + */ + public Trigger {{ trigger.name }}(double threshold) { + return {{ trigger.name }}(threshold, getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the axis value of the {{ trigger.DocName }}. The returned trigger + * will be true when the axis value is greater than 0.5. + * + * @return a Trigger instance that is true when the {{ trigger.DocName }}'s axis exceeds 0.5, attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger {{ trigger.name }}() { + return {{ trigger.name }}(0.5); + } +{% endif -%} +{% endfor -%} +{% for stick in sticks %} + /** + * Get the {{ stick.NameParts[1] }} axis value of {{ stick.NameParts[0] }} side of the controller. {{ stick.PositiveDirection }} is positive. + * + * @return The axis value. + */ + public double get{{ stick.NameParts|map("capitalize")|join }}() { + return m_hid.get{{ stick.NameParts|map("capitalize")|join }}(); + } +{% endfor -%} +{% for trigger in triggers %} + /** + * Get the {{ trigger.DocName }} axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double get{{ capitalize_first(trigger.name) }}Axis() { + return m_hid.get{{ capitalize_first(trigger.name) }}Axis(); + } +{% endfor -%} +} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java new file mode 100644 index 00000000000..03c18f38eb2 --- /dev/null +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -0,0 +1,417 @@ +// 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. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY + +package org.wpilib.commands3.button; + +import edu.wpi.first.wpilibj.PS4Controller; +import edu.wpi.first.wpilibj.event.EventLoop; +import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; + +/** + * A version of {@link PS4Controller} with {@link Trigger} factories for command-based. + * + * @see PS4Controller + */ +@SuppressWarnings("MethodName") +public class CommandPS4Controller extends CommandGenericHID { + private final PS4Controller m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandPS4Controller(int port) { + super(port); + m_hid = new PS4Controller(port); + } + + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandPS4Controller(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new PS4Controller(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public PS4Controller getHID() { + return m_hid; + } + + /** + * Constructs a Trigger instance around the square button's digital signal. + * + * @return a Trigger instance representing the square button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #square(EventLoop) + */ + public Trigger square() { + return square(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the square button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the square button's digital signal attached + * to the given loop. + */ + public Trigger square(EventLoop loop) { + return button(PS4Controller.Button.kSquare.value, loop); + } + + /** + * Constructs a Trigger instance around the cross button's digital signal. + * + * @return a Trigger instance representing the cross button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #cross(EventLoop) + */ + public Trigger cross() { + return cross(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the cross button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the cross button's digital signal attached + * to the given loop. + */ + public Trigger cross(EventLoop loop) { + return button(PS4Controller.Button.kCross.value, loop); + } + + /** + * Constructs a Trigger instance around the circle button's digital signal. + * + * @return a Trigger instance representing the circle button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #circle(EventLoop) + */ + public Trigger circle() { + return circle(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the circle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the circle button's digital signal attached + * to the given loop. + */ + public Trigger circle(EventLoop loop) { + return button(PS4Controller.Button.kCircle.value, loop); + } + + /** + * Constructs a Trigger instance around the triangle button's digital signal. + * + * @return a Trigger instance representing the triangle button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #triangle(EventLoop) + */ + public Trigger triangle() { + return triangle(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the triangle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the triangle button's digital signal attached + * to the given loop. + */ + public Trigger triangle(EventLoop loop) { + return button(PS4Controller.Button.kTriangle.value, loop); + } + + /** + * Constructs a Trigger instance around the left trigger 1 button's digital signal. + * + * @return a Trigger instance representing the left trigger 1 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L1(EventLoop) + */ + public Trigger L1() { + return L1(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left trigger 1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left trigger 1 button's digital signal attached + * to the given loop. + */ + public Trigger L1(EventLoop loop) { + return button(PS4Controller.Button.kL1.value, loop); + } + + /** + * Constructs a Trigger instance around the right trigger 1 button's digital signal. + * + * @return a Trigger instance representing the right trigger 1 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R1(EventLoop) + */ + public Trigger R1() { + return R1(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right trigger 1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right trigger 1 button's digital signal attached + * to the given loop. + */ + public Trigger R1(EventLoop loop) { + return button(PS4Controller.Button.kR1.value, loop); + } + + /** + * Constructs a Trigger instance around the left trigger 2 button's digital signal. + * + * @return a Trigger instance representing the left trigger 2 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L2(EventLoop) + */ + public Trigger L2() { + return L2(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left trigger 2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left trigger 2 button's digital signal attached + * to the given loop. + */ + public Trigger L2(EventLoop loop) { + return button(PS4Controller.Button.kL2.value, loop); + } + + /** + * Constructs a Trigger instance around the right trigger 2 button's digital signal. + * + * @return a Trigger instance representing the right trigger 2 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R2(EventLoop) + */ + public Trigger R2() { + return R2(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right trigger 2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right trigger 2 button's digital signal attached + * to the given loop. + */ + public Trigger R2(EventLoop loop) { + return button(PS4Controller.Button.kR2.value, loop); + } + + /** + * Constructs a Trigger instance around the share button's digital signal. + * + * @return a Trigger instance representing the share button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #share(EventLoop) + */ + public Trigger share() { + return share(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the share button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the share button's digital signal attached + * to the given loop. + */ + public Trigger share(EventLoop loop) { + return button(PS4Controller.Button.kShare.value, loop); + } + + /** + * Constructs a Trigger instance around the options button's digital signal. + * + * @return a Trigger instance representing the options button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #options(EventLoop) + */ + public Trigger options() { + return options(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the options button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the options button's digital signal attached + * to the given loop. + */ + public Trigger options(EventLoop loop) { + return button(PS4Controller.Button.kOptions.value, loop); + } + + /** + * Constructs a Trigger instance around the L3 (left stick) button's digital signal. + * + * @return a Trigger instance representing the L3 (left stick) button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L3(EventLoop) + */ + public Trigger L3() { + return L3(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the L3 (left stick) button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the L3 (left stick) button's digital signal attached + * to the given loop. + */ + public Trigger L3(EventLoop loop) { + return button(PS4Controller.Button.kL3.value, loop); + } + + /** + * Constructs a Trigger instance around the R3 (right stick) button's digital signal. + * + * @return a Trigger instance representing the R3 (right stick) button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R3(EventLoop) + */ + public Trigger R3() { + return R3(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the R3 (right stick) button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the R3 (right stick) button's digital signal attached + * to the given loop. + */ + public Trigger R3(EventLoop loop) { + return button(PS4Controller.Button.kR3.value, loop); + } + + /** + * Constructs a Trigger instance around the PlayStation button's digital signal. + * + * @return a Trigger instance representing the PlayStation button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #PS(EventLoop) + */ + public Trigger PS() { + return PS(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the PlayStation button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the PlayStation button's digital signal attached + * to the given loop. + */ + public Trigger PS(EventLoop loop) { + return button(PS4Controller.Button.kPS.value, loop); + } + + /** + * Constructs a Trigger instance around the touchpad button's digital signal. + * + * @return a Trigger instance representing the touchpad button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #touchpad(EventLoop) + */ + public Trigger touchpad() { + return touchpad(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the touchpad button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the touchpad button's digital signal attached + * to the given loop. + */ + public Trigger touchpad(EventLoop loop) { + return button(PS4Controller.Button.kTouchpad.value, loop); + } + + /** + * Get the X axis value of left side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the Y axis value of left side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the X axis value of right side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of right side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the left trigger 2 axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getL2Axis() { + return m_hid.getL2Axis(); + } + + /** + * Get the right trigger 2 axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getR2Axis() { + return m_hid.getR2Axis(); + } +} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java new file mode 100644 index 00000000000..670423824b1 --- /dev/null +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -0,0 +1,417 @@ +// 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. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY + +package org.wpilib.commands3.button; + +import edu.wpi.first.wpilibj.PS5Controller; +import edu.wpi.first.wpilibj.event.EventLoop; +import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; + +/** + * A version of {@link PS5Controller} with {@link Trigger} factories for command-based. + * + * @see PS5Controller + */ +@SuppressWarnings("MethodName") +public class CommandPS5Controller extends CommandGenericHID { + private final PS5Controller m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandPS5Controller(int port) { + super(port); + m_hid = new PS5Controller(port); + } + + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandPS5Controller(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new PS5Controller(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public PS5Controller getHID() { + return m_hid; + } + + /** + * Constructs a Trigger instance around the square button's digital signal. + * + * @return a Trigger instance representing the square button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #square(EventLoop) + */ + public Trigger square() { + return square(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the square button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the square button's digital signal attached + * to the given loop. + */ + public Trigger square(EventLoop loop) { + return button(PS5Controller.Button.kSquare.value, loop); + } + + /** + * Constructs a Trigger instance around the cross button's digital signal. + * + * @return a Trigger instance representing the cross button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #cross(EventLoop) + */ + public Trigger cross() { + return cross(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the cross button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the cross button's digital signal attached + * to the given loop. + */ + public Trigger cross(EventLoop loop) { + return button(PS5Controller.Button.kCross.value, loop); + } + + /** + * Constructs a Trigger instance around the circle button's digital signal. + * + * @return a Trigger instance representing the circle button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #circle(EventLoop) + */ + public Trigger circle() { + return circle(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the circle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the circle button's digital signal attached + * to the given loop. + */ + public Trigger circle(EventLoop loop) { + return button(PS5Controller.Button.kCircle.value, loop); + } + + /** + * Constructs a Trigger instance around the triangle button's digital signal. + * + * @return a Trigger instance representing the triangle button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #triangle(EventLoop) + */ + public Trigger triangle() { + return triangle(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the triangle button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the triangle button's digital signal attached + * to the given loop. + */ + public Trigger triangle(EventLoop loop) { + return button(PS5Controller.Button.kTriangle.value, loop); + } + + /** + * Constructs a Trigger instance around the left trigger 1 button's digital signal. + * + * @return a Trigger instance representing the left trigger 1 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L1(EventLoop) + */ + public Trigger L1() { + return L1(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left trigger 1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left trigger 1 button's digital signal attached + * to the given loop. + */ + public Trigger L1(EventLoop loop) { + return button(PS5Controller.Button.kL1.value, loop); + } + + /** + * Constructs a Trigger instance around the right trigger 1 button's digital signal. + * + * @return a Trigger instance representing the right trigger 1 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R1(EventLoop) + */ + public Trigger R1() { + return R1(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right trigger 1 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right trigger 1 button's digital signal attached + * to the given loop. + */ + public Trigger R1(EventLoop loop) { + return button(PS5Controller.Button.kR1.value, loop); + } + + /** + * Constructs a Trigger instance around the left trigger 2 button's digital signal. + * + * @return a Trigger instance representing the left trigger 2 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L2(EventLoop) + */ + public Trigger L2() { + return L2(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left trigger 2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left trigger 2 button's digital signal attached + * to the given loop. + */ + public Trigger L2(EventLoop loop) { + return button(PS5Controller.Button.kL2.value, loop); + } + + /** + * Constructs a Trigger instance around the right trigger 2 button's digital signal. + * + * @return a Trigger instance representing the right trigger 2 button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R2(EventLoop) + */ + public Trigger R2() { + return R2(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right trigger 2 button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right trigger 2 button's digital signal attached + * to the given loop. + */ + public Trigger R2(EventLoop loop) { + return button(PS5Controller.Button.kR2.value, loop); + } + + /** + * Constructs a Trigger instance around the create button's digital signal. + * + * @return a Trigger instance representing the create button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #create(EventLoop) + */ + public Trigger create() { + return create(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the create button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the create button's digital signal attached + * to the given loop. + */ + public Trigger create(EventLoop loop) { + return button(PS5Controller.Button.kCreate.value, loop); + } + + /** + * Constructs a Trigger instance around the options button's digital signal. + * + * @return a Trigger instance representing the options button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #options(EventLoop) + */ + public Trigger options() { + return options(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the options button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the options button's digital signal attached + * to the given loop. + */ + public Trigger options(EventLoop loop) { + return button(PS5Controller.Button.kOptions.value, loop); + } + + /** + * Constructs a Trigger instance around the L3 (left stick) button's digital signal. + * + * @return a Trigger instance representing the L3 (left stick) button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #L3(EventLoop) + */ + public Trigger L3() { + return L3(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the L3 (left stick) button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the L3 (left stick) button's digital signal attached + * to the given loop. + */ + public Trigger L3(EventLoop loop) { + return button(PS5Controller.Button.kL3.value, loop); + } + + /** + * Constructs a Trigger instance around the R3 (right stick) button's digital signal. + * + * @return a Trigger instance representing the R3 (right stick) button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #R3(EventLoop) + */ + public Trigger R3() { + return R3(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the R3 (right stick) button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the R3 (right stick) button's digital signal attached + * to the given loop. + */ + public Trigger R3(EventLoop loop) { + return button(PS5Controller.Button.kR3.value, loop); + } + + /** + * Constructs a Trigger instance around the PlayStation button's digital signal. + * + * @return a Trigger instance representing the PlayStation button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #PS(EventLoop) + */ + public Trigger PS() { + return PS(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the PlayStation button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the PlayStation button's digital signal attached + * to the given loop. + */ + public Trigger PS(EventLoop loop) { + return button(PS5Controller.Button.kPS.value, loop); + } + + /** + * Constructs a Trigger instance around the touchpad button's digital signal. + * + * @return a Trigger instance representing the touchpad button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #touchpad(EventLoop) + */ + public Trigger touchpad() { + return touchpad(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the touchpad button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the touchpad button's digital signal attached + * to the given loop. + */ + public Trigger touchpad(EventLoop loop) { + return button(PS5Controller.Button.kTouchpad.value, loop); + } + + /** + * Get the X axis value of left side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the Y axis value of left side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the X axis value of right side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of right side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the left trigger 2 axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getL2Axis() { + return m_hid.getL2Axis(); + } + + /** + * Get the right trigger 2 axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getR2Axis() { + return m_hid.getR2Axis(); + } +} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java new file mode 100644 index 00000000000..254f0bfc522 --- /dev/null +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -0,0 +1,419 @@ +// 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. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY + +package org.wpilib.commands3.button; + +import edu.wpi.first.wpilibj.StadiaController; +import edu.wpi.first.wpilibj.event.EventLoop; +import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; + +/** + * A version of {@link StadiaController} with {@link Trigger} factories for command-based. + * + * @see StadiaController + */ +@SuppressWarnings("MethodName") +public class CommandStadiaController extends CommandGenericHID { + private final StadiaController m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandStadiaController(int port) { + super(port); + m_hid = new StadiaController(port); + } + + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandStadiaController(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new StadiaController(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public StadiaController getHID() { + return m_hid; + } + + /** + * Constructs a Trigger instance around the A button's digital signal. + * + * @return a Trigger instance representing the A button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #a(EventLoop) + */ + public Trigger a() { + return a(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the A button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the A button's digital signal attached + * to the given loop. + */ + public Trigger a(EventLoop loop) { + return button(StadiaController.Button.kA.value, loop); + } + + /** + * Constructs a Trigger instance around the B button's digital signal. + * + * @return a Trigger instance representing the B button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #b(EventLoop) + */ + public Trigger b() { + return b(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the B button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the B button's digital signal attached + * to the given loop. + */ + public Trigger b(EventLoop loop) { + return button(StadiaController.Button.kB.value, loop); + } + + /** + * Constructs a Trigger instance around the X button's digital signal. + * + * @return a Trigger instance representing the X button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #x(EventLoop) + */ + public Trigger x() { + return x(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the X button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the X button's digital signal attached + * to the given loop. + */ + public Trigger x(EventLoop loop) { + return button(StadiaController.Button.kX.value, loop); + } + + /** + * Constructs a Trigger instance around the Y button's digital signal. + * + * @return a Trigger instance representing the Y button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #y(EventLoop) + */ + public Trigger y() { + return y(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the Y button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the Y button's digital signal attached + * to the given loop. + */ + public Trigger y(EventLoop loop) { + return button(StadiaController.Button.kY.value, loop); + } + + /** + * Constructs a Trigger instance around the left bumper button's digital signal. + * + * @return a Trigger instance representing the left bumper button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftBumper(EventLoop) + */ + public Trigger leftBumper() { + return leftBumper(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left bumper button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left bumper button's digital signal attached + * to the given loop. + */ + public Trigger leftBumper(EventLoop loop) { + return button(StadiaController.Button.kLeftBumper.value, loop); + } + + /** + * Constructs a Trigger instance around the right bumper button's digital signal. + * + * @return a Trigger instance representing the right bumper button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightBumper(EventLoop) + */ + public Trigger rightBumper() { + return rightBumper(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right bumper button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right bumper button's digital signal attached + * to the given loop. + */ + public Trigger rightBumper(EventLoop loop) { + return button(StadiaController.Button.kRightBumper.value, loop); + } + + /** + * Constructs a Trigger instance around the left stick button's digital signal. + * + * @return a Trigger instance representing the left stick button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftStick(EventLoop) + */ + public Trigger leftStick() { + return leftStick(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left stick button's digital signal attached + * to the given loop. + */ + public Trigger leftStick(EventLoop loop) { + return button(StadiaController.Button.kLeftStick.value, loop); + } + + /** + * Constructs a Trigger instance around the right stick button's digital signal. + * + * @return a Trigger instance representing the right stick button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightStick(EventLoop) + */ + public Trigger rightStick() { + return rightStick(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right stick button's digital signal attached + * to the given loop. + */ + public Trigger rightStick(EventLoop loop) { + return button(StadiaController.Button.kRightStick.value, loop); + } + + /** + * Constructs a Trigger instance around the ellipses button's digital signal. + * + * @return a Trigger instance representing the ellipses button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #ellipses(EventLoop) + */ + public Trigger ellipses() { + return ellipses(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the ellipses button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the ellipses button's digital signal attached + * to the given loop. + */ + public Trigger ellipses(EventLoop loop) { + return button(StadiaController.Button.kEllipses.value, loop); + } + + /** + * Constructs a Trigger instance around the hamburger button's digital signal. + * + * @return a Trigger instance representing the hamburger button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #hamburger(EventLoop) + */ + public Trigger hamburger() { + return hamburger(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the hamburger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the hamburger button's digital signal attached + * to the given loop. + */ + public Trigger hamburger(EventLoop loop) { + return button(StadiaController.Button.kHamburger.value, loop); + } + + /** + * Constructs a Trigger instance around the stadia button's digital signal. + * + * @return a Trigger instance representing the stadia button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #stadia(EventLoop) + */ + public Trigger stadia() { + return stadia(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the stadia button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the stadia button's digital signal attached + * to the given loop. + */ + public Trigger stadia(EventLoop loop) { + return button(StadiaController.Button.kStadia.value, loop); + } + + /** + * Constructs a Trigger instance around the right trigger button's digital signal. + * + * @return a Trigger instance representing the right trigger button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightTrigger(EventLoop) + */ + public Trigger rightTrigger() { + return rightTrigger(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right trigger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right trigger button's digital signal attached + * to the given loop. + */ + public Trigger rightTrigger(EventLoop loop) { + return button(StadiaController.Button.kRightTrigger.value, loop); + } + + /** + * Constructs a Trigger instance around the left trigger button's digital signal. + * + * @return a Trigger instance representing the left trigger button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftTrigger(EventLoop) + */ + public Trigger leftTrigger() { + return leftTrigger(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left trigger button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left trigger button's digital signal attached + * to the given loop. + */ + public Trigger leftTrigger(EventLoop loop) { + return button(StadiaController.Button.kLeftTrigger.value, loop); + } + + /** + * Constructs a Trigger instance around the google button's digital signal. + * + * @return a Trigger instance representing the google button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #google(EventLoop) + */ + public Trigger google() { + return google(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the google button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the google button's digital signal attached + * to the given loop. + */ + public Trigger google(EventLoop loop) { + return button(StadiaController.Button.kGoogle.value, loop); + } + + /** + * Constructs a Trigger instance around the frame button's digital signal. + * + * @return a Trigger instance representing the frame button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #frame(EventLoop) + */ + public Trigger frame() { + return frame(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the frame button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the frame button's digital signal attached + * to the given loop. + */ + public Trigger frame(EventLoop loop) { + return button(StadiaController.Button.kFrame.value, loop); + } + + /** + * Get the X axis value of left side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } +} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java new file mode 100644 index 00000000000..2bb4b437e47 --- /dev/null +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -0,0 +1,407 @@ +// 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. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY + +package org.wpilib.commands3.button; + +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.event.EventLoop; +import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.Trigger; + +/** + * A version of {@link XboxController} with {@link Trigger} factories for command-based. + * + * @see XboxController + */ +@SuppressWarnings("MethodName") +public class CommandXboxController extends CommandGenericHID { + private final XboxController m_hid; + + /** + * Construct an instance of a controller. + * + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandXboxController(int port) { + super(port); + m_hid = new XboxController(port); + } + + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandXboxController(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new XboxController(port); + } + + /** + * Get the underlying GenericHID object. + * + * @return the wrapped GenericHID object + */ + @Override + public XboxController getHID() { + return m_hid; + } + + /** + * Constructs a Trigger instance around the A button's digital signal. + * + * @return a Trigger instance representing the A button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #a(EventLoop) + */ + public Trigger a() { + return a(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the A button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the A button's digital signal attached + * to the given loop. + */ + public Trigger a(EventLoop loop) { + return button(XboxController.Button.kA.value, loop); + } + + /** + * Constructs a Trigger instance around the B button's digital signal. + * + * @return a Trigger instance representing the B button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #b(EventLoop) + */ + public Trigger b() { + return b(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the B button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the B button's digital signal attached + * to the given loop. + */ + public Trigger b(EventLoop loop) { + return button(XboxController.Button.kB.value, loop); + } + + /** + * Constructs a Trigger instance around the X button's digital signal. + * + * @return a Trigger instance representing the X button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #x(EventLoop) + */ + public Trigger x() { + return x(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the X button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the X button's digital signal attached + * to the given loop. + */ + public Trigger x(EventLoop loop) { + return button(XboxController.Button.kX.value, loop); + } + + /** + * Constructs a Trigger instance around the Y button's digital signal. + * + * @return a Trigger instance representing the Y button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #y(EventLoop) + */ + public Trigger y() { + return y(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the Y button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the Y button's digital signal attached + * to the given loop. + */ + public Trigger y(EventLoop loop) { + return button(XboxController.Button.kY.value, loop); + } + + /** + * Constructs a Trigger instance around the left bumper button's digital signal. + * + * @return a Trigger instance representing the left bumper button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftBumper(EventLoop) + */ + public Trigger leftBumper() { + return leftBumper(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left bumper button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left bumper button's digital signal attached + * to the given loop. + */ + public Trigger leftBumper(EventLoop loop) { + return button(XboxController.Button.kLeftBumper.value, loop); + } + + /** + * Constructs a Trigger instance around the right bumper button's digital signal. + * + * @return a Trigger instance representing the right bumper button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightBumper(EventLoop) + */ + public Trigger rightBumper() { + return rightBumper(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right bumper button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right bumper button's digital signal attached + * to the given loop. + */ + public Trigger rightBumper(EventLoop loop) { + return button(XboxController.Button.kRightBumper.value, loop); + } + + /** + * Constructs a Trigger instance around the back button's digital signal. + * + * @return a Trigger instance representing the back button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #back(EventLoop) + */ + public Trigger back() { + return back(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the back button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the back button's digital signal attached + * to the given loop. + */ + public Trigger back(EventLoop loop) { + return button(XboxController.Button.kBack.value, loop); + } + + /** + * Constructs a Trigger instance around the start button's digital signal. + * + * @return a Trigger instance representing the start button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #start(EventLoop) + */ + public Trigger start() { + return start(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the start button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the start button's digital signal attached + * to the given loop. + */ + public Trigger start(EventLoop loop) { + return button(XboxController.Button.kStart.value, loop); + } + + /** + * Constructs a Trigger instance around the left stick button's digital signal. + * + * @return a Trigger instance representing the left stick button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #leftStick(EventLoop) + */ + public Trigger leftStick() { + return leftStick(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the left stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the left stick button's digital signal attached + * to the given loop. + */ + public Trigger leftStick(EventLoop loop) { + return button(XboxController.Button.kLeftStick.value, loop); + } + + /** + * Constructs a Trigger instance around the right stick button's digital signal. + * + * @return a Trigger instance representing the right stick button's digital signal attached + * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #rightStick(EventLoop) + */ + public Trigger rightStick() { + return rightStick(getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the right stick button's digital signal. + * + * @param loop the event loop instance to attach the event to. + * @return a Trigger instance representing the right stick button's digital signal attached + * to the given loop. + */ + public Trigger rightStick(EventLoop loop) { + return button(XboxController.Button.kRightStick.value, loop); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @param loop the event loop instance to attach the Trigger to. + * @return a Trigger instance that is true when the left trigger's axis exceeds the provided + * threshold, attached to the given event loop + */ + public Trigger leftTrigger(double threshold, EventLoop loop) { + return axisGreaterThan(XboxController.Axis.kLeftTrigger.value, threshold, loop); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @return a Trigger instance that is true when the left trigger's axis exceeds the provided + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler + * button loop}. + */ + public Trigger leftTrigger(double threshold) { + return leftTrigger(threshold, getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger + * will be true when the axis value is greater than 0.5. + * + * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger leftTrigger() { + return leftTrigger(0.5); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @param loop the event loop instance to attach the Trigger to. + * @return a Trigger instance that is true when the right trigger's axis exceeds the provided + * threshold, attached to the given event loop + */ + public Trigger rightTrigger(double threshold, EventLoop loop) { + return axisGreaterThan(XboxController.Axis.kRightTrigger.value, threshold, loop); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned + * trigger will be true when the axis value is greater than {@code threshold}. + * + * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value + * should be in the range [0, 1] where 0 is the unpressed state of the axis. + * @return a Trigger instance that is true when the right trigger's axis exceeds the provided + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler + * button loop}. + */ + public Trigger rightTrigger(double threshold) { + return rightTrigger(threshold, getScheduler().getDefaultEventLoop()); + } + + /** + * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger + * will be true when the axis value is greater than 0.5. + * + * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to + * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + */ + public Trigger rightTrigger() { + return rightTrigger(0.5); + } + + /** + * Get the X axis value of left side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getLeftX() { + return m_hid.getLeftX(); + } + + /** + * Get the X axis value of right side of the controller. Right is positive. + * + * @return The axis value. + */ + public double getRightX() { + return m_hid.getRightX(); + } + + /** + * Get the Y axis value of left side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getLeftY() { + return m_hid.getLeftY(); + } + + /** + * Get the Y axis value of right side of the controller. Back is positive. + * + * @return The axis value. + */ + public double getRightY() { + return m_hid.getRightY(); + } + + /** + * Get the left trigger axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getLeftTriggerAxis() { + return m_hid.getLeftTriggerAxis(); + } + + /** + * Get the right trigger axis value of the controller. Note that this axis is bound to the + * range of [0, 1] as opposed to the usual [-1, 1]. + * + * @return The axis value. + */ + public double getRightTriggerAxis() { + return m_hid.getRightTriggerAxis(); + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index f05fa5a80f5..5e3e6b093ac 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -4,7 +4,11 @@ package org.wpilib.commands3.button; +import edu.wpi.first.math.Pair; import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.event.EventLoop; +import java.util.HashMap; +import java.util.Map; import org.wpilib.commands3.Scheduler; import org.wpilib.commands3.Trigger; @@ -14,17 +18,37 @@ * @see GenericHID */ public class CommandGenericHID { + protected final Scheduler m_scheduler; private final GenericHID m_hid; + private final Map> m_buttonCache = new HashMap<>(); + private final Map, Trigger>> m_axisLessThanCache = + new HashMap<>(); + private final Map, Trigger>> m_axisGreaterThanCache = + new HashMap<>(); + private final Map, Trigger>> + m_axisMagnitudeGreaterThanCache = new HashMap<>(); + private final Map> m_povCache = new HashMap<>(); /** * Construct an instance of a device. * + * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the device is plugged into. */ - public CommandGenericHID(int port) { + public CommandGenericHID(Scheduler scheduler, int port) { + m_scheduler = scheduler; m_hid = new GenericHID(port); } + /** + * Construct an instance of a device. + * + * @param port The port index on the Driver Station that the device is plugged into. + */ + public CommandGenericHID(int port) { + this(Scheduler.getDefault(), port); + } + /** * Get the underlying GenericHID object. * @@ -39,28 +63,30 @@ public GenericHID getHID() { * * @param button the button index * @return an event instance representing the button's digital signal attached to the {@link - * Scheduler#getDefault() default scheduler button scheduler}. - * @see #button(int, Scheduler) + * Scheduler#getDefaultEventLoop() default scheduler button loop}. + * @see #button(int, EventLoop) */ public Trigger button(int button) { - return this.button(button, Scheduler.getDefault()); + return button(button, m_scheduler.getDefaultEventLoop()); } /** * Constructs an event instance around this button's digital signal. * * @param button the button index - * @param scheduler the scheduler instance to attach the event to. - * @return an event instance representing the button's digital signal attached to the given - * scheduler. + * @param loop the event loop instance to attach the event to. + * @return an event instance representing the button's digital signal attached to the given loop. */ - public Trigger button(int button, Scheduler scheduler) { - return new Trigger(scheduler, () -> m_hid.getRawButton(button)); + public Trigger button(int button, EventLoop loop) { + var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + button, k -> new Trigger(m_scheduler, loop, () -> m_hid.getRawButton(k))); } /** * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, - * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button + * loop}. * *

The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, * upper-left is 315). @@ -69,7 +95,7 @@ public Trigger button(int button, Scheduler scheduler) { * @return a Trigger instance based around this angle of a POV on the HID. */ public Trigger pov(int angle) { - return pov(0, angle, Scheduler.getDefault()); + return pov(0, angle, m_scheduler.getDefaultEventLoop()); } /** @@ -80,18 +106,22 @@ public Trigger pov(int angle) { * * @param pov index of the POV to read (starting at 0). Defaults to 0. * @param angle POV angle in degrees, or -1 for the center / not pressed. - * @param scheduler the scheduler instance to attach the event to. Defaults to {@link - * Scheduler#getDefault() the default command scheduler button scheduler}. + * @param loop the event loop instance to attach the event to. Defaults to {@link + * Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * @return a Trigger instance based around this angle of a POV on the HID. */ - public Trigger pov(int pov, int angle, Scheduler scheduler) { - return new Trigger(scheduler, () -> m_hid.getPOV(pov) == angle); + public Trigger pov(int pov, int angle, EventLoop loop) { + var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>()); + // angle can be -1, so use 3600 instead of 360 + return cache.computeIfAbsent( + pov * 3600 + angle, + k -> new Trigger(m_scheduler, loop, () -> m_hid.getPOV(pov) == angle)); } /** * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV - * on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button - * scheduler}. + * on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 0 degree angle of a POV on the HID. */ @@ -101,8 +131,8 @@ public Trigger povUp() { /** * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler - * button scheduler}. + * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default + * command scheduler button loop}. * * @return a Trigger instance based around the 45 degree angle of a POV on the HID. */ @@ -112,8 +142,8 @@ public Trigger povUpRight() { /** * Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button - * scheduler}. + * POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 90 degree angle of a POV on the HID. */ @@ -123,8 +153,8 @@ public Trigger povRight() { /** * Constructs a Trigger instance based around the 135 degree angle (right down) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command - * scheduler button scheduler}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the + * default command scheduler button loop}. * * @return a Trigger instance based around the 135 degree angle of a POV on the HID. */ @@ -134,8 +164,8 @@ public Trigger povDownRight() { /** * Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button - * scheduler}. + * POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 180 degree angle of a POV on the HID. */ @@ -145,8 +175,8 @@ public Trigger povDown() { /** * Constructs a Trigger instance based around the 225 degree angle (down left) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command - * scheduler button scheduler}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the + * default command scheduler button loop}. * * @return a Trigger instance based around the 225 degree angle of a POV on the HID. */ @@ -156,8 +186,8 @@ public Trigger povDownLeft() { /** * Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0) - * POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler button - * scheduler}. + * POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 270 degree angle of a POV on the HID. */ @@ -167,8 +197,8 @@ public Trigger povLeft() { /** * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command scheduler - * button scheduler}. + * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default + * command scheduler button loop}. * * @return a Trigger instance based around the 315 degree angle of a POV on the HID. */ @@ -178,8 +208,8 @@ public Trigger povUpLeft() { /** * Constructs a Trigger instance based around the center (not pressed) position of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefault() the default command - * scheduler button scheduler}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the + * default command scheduler button loop}. * * @return a Trigger instance based around the center position of a POV on the HID. */ @@ -189,7 +219,8 @@ public Trigger povCenter() { /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button + * loop}. * * @param axis The axis to read, starting at 0 * @param threshold The value below which this trigger should return true. @@ -197,27 +228,30 @@ public Trigger povCenter() { * threshold. */ public Trigger axisLessThan(int axis, double threshold) { - return axisLessThan(axis, threshold, Scheduler.getDefault()); + return axisLessThan(axis, threshold, m_scheduler.getDefaultEventLoop()); } /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to the given scheduler. + * attached to the given loop. * * @param axis The axis to read, starting at 0 * @param threshold The value below which this trigger should return true. - * @param scheduler the scheduler instance to attach the trigger to + * @param loop the event loop instance to attach the trigger to * @return a Trigger instance that is true when the axis value is less than the provided * threshold. */ - public Trigger axisLessThan(int axis, double threshold, Scheduler scheduler) { - return new Trigger( - scheduler, m_hid.axisLessThan(axis, threshold, scheduler.getDefaultEventLoop())); + public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { + var cache = m_axisLessThanCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + Pair.of(axis, threshold), + k -> new Trigger(m_scheduler, loop, () -> getRawAxis(axis) < threshold)); } /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getDefault() the default command scheduler button scheduler}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button + * loop}. * * @param axis The axis to read, starting at 0 * @param threshold The value above which this trigger should return true. @@ -225,22 +259,55 @@ public Trigger axisLessThan(int axis, double threshold, Scheduler scheduler) { * threshold. */ public Trigger axisGreaterThan(int axis, double threshold) { - return axisGreaterThan(axis, threshold, Scheduler.getDefault()); + return axisGreaterThan(axis, threshold, m_scheduler.getDefaultEventLoop()); } /** * Constructs a Trigger instance that is true when the axis value is greater than {@code - * threshold}, attached to the given scheduler. + * threshold}, attached to the given loop. * * @param axis The axis to read, starting at 0 * @param threshold The value above which this trigger should return true. - * @param scheduler the scheduler instance to attach the trigger to. + * @param loop the event loop instance to attach the trigger to. * @return a Trigger instance that is true when the axis value is greater than the provided * threshold. */ - public Trigger axisGreaterThan(int axis, double threshold, Scheduler scheduler) { - return new Trigger( - scheduler, m_hid.axisGreaterThan(axis, threshold, scheduler.getDefaultEventLoop())); + public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) { + var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + Pair.of(axis, threshold), + k -> new Trigger(m_scheduler, loop, () -> getRawAxis(axis) > threshold)); + } + + /** + * Constructs a Trigger instance that is true when the axis magnitude value is greater than {@code + * threshold}, attached to the given loop. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value above which this trigger should return true. + * @param loop the event loop instance to attach the trigger to. + * @return a Trigger instance that is true when the axis magnitude value is greater than the + * provided threshold. + */ + public Trigger axisMagnitudeGreaterThan(int axis, double threshold, EventLoop loop) { + var cache = m_axisMagnitudeGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + Pair.of(axis, threshold), + k -> new Trigger(m_scheduler, loop, () -> Math.abs(getRawAxis(axis)) > threshold)); + } + + /** + * Constructs a Trigger instance that is true when the axis magnitude value is greater than {@code + * threshold}, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. + * + * @param axis The axis to read, starting at 0 + * @param threshold The value above which this trigger should return true. + * @return a Trigger instance that is true when the deadbanded axis value is active (non-zero). + */ + public Trigger axisMagnitudeGreaterThan(int axis, double threshold) { + return axisMagnitudeGreaterThan( + axis, threshold, m_scheduler.getDefaultEventLoop()); } /** @@ -252,4 +319,28 @@ public Trigger axisGreaterThan(int axis, double threshold, Scheduler scheduler) public double getRawAxis(int axis) { return m_hid.getRawAxis(axis); } + + /** + * Set the rumble output for the HID. The DS currently supports 2 rumble values, left rumble and + * right rumble. + * + * @param type Which rumble value to set + * @param value The normalized value (0 to 1) to set the rumble to + */ + public void setRumble(GenericHID.RumbleType type, double value) { + m_hid.setRumble(type, value); + } + + /** + * Get if the HID is connected. + * + * @return true if the HID is connected + */ + public boolean isConnected() { + return m_hid.isConnected(); + } + + protected final Scheduler getScheduler() { + return m_scheduler; + } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java index d3998e27581..cc7bf9a335b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandJoystick.java @@ -5,6 +5,7 @@ package org.wpilib.commands3.button; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.event.EventLoop; import org.wpilib.commands3.Scheduler; import org.wpilib.commands3.Trigger; @@ -26,6 +27,17 @@ public CommandJoystick(int port) { m_hid = new Joystick(port); } + /** + * Construct an instance of a controller. + * + * @param scheduler The scheduler that should execute the triggered commands. + * @param port The port index on the Driver Station that the controller is plugged into. + */ + public CommandJoystick(Scheduler scheduler, int port) { + super(scheduler, port); + m_hid = new Joystick(port); + } + /** * Get the underlying GenericHID object. * @@ -41,21 +53,21 @@ public Joystick getHID() { * * @return an event instance representing the trigger button's digital signal attached to the * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #trigger(Scheduler) + * @see #trigger(EventLoop) */ public Trigger trigger() { - return trigger(Scheduler.getDefault()); + return trigger(getScheduler().getDefaultEventLoop()); } /** * Constructs an event instance around the trigger button's digital signal. * - * @param scheduler the scheduler instance to attach the event to. + * @param loop the event loop instance to attach the event to. * @return an event instance representing the trigger button's digital signal attached to the - * given scheduler. + * given loop. */ - public Trigger trigger(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.trigger(scheduler.getDefaultEventLoop())); + public Trigger trigger(EventLoop loop) { + return button(Joystick.ButtonType.kTrigger.value, loop); } /** @@ -63,21 +75,21 @@ public Trigger trigger(Scheduler scheduler) { * * @return an event instance representing the top button's digital signal attached to the {@link * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #top(Scheduler) + * @see #top(EventLoop) */ public Trigger top() { - return top(Scheduler.getDefault()); + return top(getScheduler().getDefaultEventLoop()); } /** * Constructs an event instance around the top button's digital signal. * - * @param scheduler the scheduler instance to attach the event to. + * @param loop the event loop instance to attach the event to. * @return an event instance representing the top button's digital signal attached to the given - * scheduler. + * loop. */ - public Trigger top(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.top(scheduler.getDefaultEventLoop())); + public Trigger top(EventLoop loop) { + return button(Joystick.ButtonType.kTop.value, loop); } /** @@ -173,6 +185,9 @@ public int getThrottleChannel() { /** * Get the x position of the HID. * + *

This depends on the mapping of the joystick connected to the current port. On most + * joysticks, positive is to the right. + * * @return the x position */ public double getX() { @@ -182,6 +197,9 @@ public double getX() { /** * Get the y position of the HID. * + *

This depends on the mapping of the joystick connected to the current port. On most + * joysticks, positive is to the back. + * * @return the y position */ public double getY() { @@ -218,8 +236,8 @@ public double getThrottle() { } /** - * Get the magnitude of the direction vector formed by the joystick's current position relative to - * its origin. + * Get the magnitude of the vector formed by the joystick's current position relative to its + * origin. * * @return The magnitude of the direction vector */ @@ -228,16 +246,26 @@ public double getMagnitude() { } /** - * Get the direction of the vector formed by the joystick and its origin in radians. + * Get the direction of the vector formed by the joystick and its origin in radians. 0 is forward + * and clockwise is positive. (Straight right is π/2.) * * @return The direction of the vector in radians */ public double getDirectionRadians() { + // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system + // A positive rotation around the X axis moves the joystick right, and a + // positive rotation around the Y axis moves the joystick backward. When + // treating them as translations, 0 radians is measured from the right + // direction, and angle increases clockwise. + // + // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) + // so that 0 radians is forward. return m_hid.getDirectionRadians(); } /** - * Get the direction of the vector formed by the joystick and its origin in degrees. + * Get the direction of the vector formed by the joystick and its origin in degrees. 0 is forward + * and clockwise is positive. (Straight right is 90.) * * @return The direction of the vector in degrees */ diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java deleted file mode 100644 index 2af81d35f31..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ /dev/null @@ -1,389 +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 org.wpilib.commands3.button; - -import edu.wpi.first.wpilibj.PS4Controller; -import org.wpilib.commands3.Scheduler; -import org.wpilib.commands3.Trigger; - -/** - * A version of {@link PS4Controller} with {@link Trigger} factories for command-based. - * - * @see PS4Controller - */ -@SuppressWarnings("MethodName") -public class CommandPS4Controller extends CommandGenericHID { - private final PS4Controller m_hid; - - /** - * Construct an instance of a device. - * - * @param port The port index on the Driver Station that the device is plugged into. - */ - public CommandPS4Controller(int port) { - super(port); - m_hid = new PS4Controller(port); - } - - /** - * Get the underlying GenericHID object. - * - * @return the wrapped GenericHID object - */ - @Override - public PS4Controller getHID() { - return m_hid; - } - - /** - * Constructs an event instance around the L2 button's digital signal. - * - * @return an event instance representing the L2 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L2() { - return L2(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L2 button's digital signal. - * - * @param scheduler the event scheduler instance to attach the event to. - * @return an event instance representing the L2 button's digital signal attached to the given - * scheduler. - */ - public Trigger L2(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L2(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R2 button's digital signal. - * - * @return an event instance representing the R2 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R2() { - return R2(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R2 button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the R2 button's digital signal attached to the given - * loop. - */ - public Trigger R2(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R2(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the L1 button's digital signal. - * - * @return an event instance representing the L1 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L1() { - return L1(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L1 button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the L1 button's digital signal attached to the given - * loop. - */ - public Trigger L1(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L1(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R1 button's digital signal. - * - * @return an event instance representing the R1 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R1() { - return R1(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R1 button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the R1 button's digital signal attached to the given - * loop. - */ - public Trigger R1(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R1(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the L3 button's digital signal. - * - * @return an event instance representing the L3 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L3() { - return L3(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L3 button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the L3 button's digital signal attached to the given - * loop. - */ - public Trigger L3(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L3(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R3 button's digital signal. - * - * @return an event instance representing the R3 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R3() { - return R3(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R3 button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the R3 button's digital signal attached to the given - * loop. - */ - public Trigger R3(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R3(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the square button's digital signal. - * - * @return an event instance representing the square button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger square() { - return square(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the square button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the square button's digital signal attached to the given - * loop. - */ - public Trigger square(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.square(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the cross button's digital signal. - * - * @return an event instance representing the cross button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger cross() { - return cross(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the cross button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the cross button's digital signal attached to the given - * loop. - */ - public Trigger cross(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.cross(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the triangle button's digital signal. - * - * @return an event instance representing the triangle button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger triangle() { - return triangle(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the triangle button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the triangle button's digital signal attached to the - * given loop. - */ - public Trigger triangle(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.triangle(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the circle button's digital signal. - * - * @return an event instance representing the circle button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger circle() { - return circle(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the circle button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the circle button's digital signal attached to the given - * loop. - */ - public Trigger circle(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.circle(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the share button's digital signal. - * - * @return an event instance representing the share button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger share() { - return share(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the share button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the share button's digital signal attached to the given - * loop. - */ - public Trigger share(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.share(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the PS button's digital signal. - * - * @return an event instance representing the PS button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger PS() { - return PS(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the PS button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the PS button's digital signal attached to the given - * loop. - */ - public Trigger PS(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.PS(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the options button's digital signal. - * - * @return an event instance representing the options button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger options() { - return options(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the options button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the options button's digital signal attached to the - * given loop. - */ - public Trigger options(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.options(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the touchpad's digital signal. - * - * @return an event instance representing the touchpad's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger touchpad() { - return touchpad(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the touchpad's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the touchpad's digital signal attached to the given - * loop. - */ - public Trigger touchpad(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.touchpad(scheduler.getDefaultEventLoop())); - } - - /** - * Get the X axis value of left side of the controller. - * - * @return the axis value. - */ - public double getLeftX() { - return m_hid.getLeftX(); - } - - /** - * Get the X axis value of right side of the controller. - * - * @return the axis value. - */ - public double getRightX() { - return m_hid.getRightX(); - } - - /** - * Get the Y axis value of left side of the controller. - * - * @return the axis value. - */ - public double getLeftY() { - return m_hid.getLeftY(); - } - - /** - * Get the Y axis value of right side of the controller. - * - * @return the axis value. - */ - public double getRightY() { - return m_hid.getRightY(); - } - - /** - * Get the L2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as - * opposed to the usual [-1, 1]. - * - * @return the axis value. - */ - public double getL2Axis() { - return m_hid.getL2Axis(); - } - - /** - * Get the R2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as - * opposed to the usual [-1, 1]. - * - * @return the axis value. - */ - public double getR2Axis() { - return m_hid.getR2Axis(); - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java deleted file mode 100644 index 04f2ade7ea1..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ /dev/null @@ -1,389 +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 org.wpilib.commands3.button; - -import edu.wpi.first.wpilibj.PS5Controller; -import org.wpilib.commands3.Scheduler; -import org.wpilib.commands3.Trigger; - -/** - * A version of {@link PS5Controller} with {@link Trigger} factories for command-based. - * - * @see PS5Controller - */ -@SuppressWarnings("MethodName") -public class CommandPS5Controller extends CommandGenericHID { - private final PS5Controller m_hid; - - /** - * Construct an instance of a device. - * - * @param port The port index on the Driver Station that the device is plugged into. - */ - public CommandPS5Controller(int port) { - super(port); - m_hid = new PS5Controller(port); - } - - /** - * Get the underlying GenericHID object. - * - * @return the wrapped GenericHID object - */ - @Override - public PS5Controller getHID() { - return m_hid; - } - - /** - * Constructs an event instance around the L2 button's digital signal. - * - * @return an event instance representing the L2 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L2() { - return L2(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L2 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the L2 button's digital signal attached to the given - * loop. - */ - public Trigger L2(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L2(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R2 button's digital signal. - * - * @return an event instance representing the R2 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R2() { - return R2(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R2 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the R2 button's digital signal attached to the given - * loop. - */ - public Trigger R2(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R2(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the L1 button's digital signal. - * - * @return an event instance representing the L1 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L1() { - return L1(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L1 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the L1 button's digital signal attached to the given - * loop. - */ - public Trigger L1(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L1(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R1 button's digital signal. - * - * @return an event instance representing the R1 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R1() { - return R1(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R1 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the R1 button's digital signal attached to the given - * loop. - */ - public Trigger R1(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R1(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the L3 button's digital signal. - * - * @return an event instance representing the L3 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger L3() { - return L3(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the L3 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the L3 button's digital signal attached to the given - * loop. - */ - public Trigger L3(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.L3(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the R3 button's digital signal. - * - * @return an event instance representing the R3 button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger R3() { - return R3(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the R3 button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the R3 button's digital signal attached to the given - * loop. - */ - public Trigger R3(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.R3(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the square button's digital signal. - * - * @return an event instance representing the square button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger square() { - return square(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the square button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the square button's digital signal attached to the given - * loop. - */ - public Trigger square(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.square(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the cross button's digital signal. - * - * @return an event instance representing the cross button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger cross() { - return cross(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the cross button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the cross button's digital signal attached to the given - * loop. - */ - public Trigger cross(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.cross(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the triangle button's digital signal. - * - * @return an event instance representing the triangle button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger triangle() { - return triangle(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the triangle button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the triangle button's digital signal attached to the - * given loop. - */ - public Trigger triangle(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.triangle(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the circle button's digital signal. - * - * @return an event instance representing the circle button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger circle() { - return circle(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the circle button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the circle button's digital signal attached to the given - * loop. - */ - public Trigger circle(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.circle(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the create button's digital signal. - * - * @return an event instance representing the create button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger create() { - return create(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the create button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the create button's digital signal attached to the given - * loop. - */ - public Trigger create(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.create(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the PS button's digital signal. - * - * @return an event instance representing the PS button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger PS() { - return PS(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the PS button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the PS button's digital signal attached to the given - * loop. - */ - public Trigger PS(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.PS(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the options button's digital signal. - * - * @return an event instance representing the options button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger options() { - return options(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the options button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the options button's digital signal attached to the - * given loop. - */ - public Trigger options(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.options(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the touchpad's digital signal. - * - * @return an event instance representing the touchpad's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger touchpad() { - return touchpad(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the touchpad's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the touchpad's digital signal attached to the given - * loop. - */ - public Trigger touchpad(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.touchpad(scheduler.getDefaultEventLoop())); - } - - /** - * Get the X axis value of left side of the controller. - * - * @return the axis value. - */ - public double getLeftX() { - return m_hid.getLeftX(); - } - - /** - * Get the X axis value of right side of the controller. - * - * @return the axis value. - */ - public double getRightX() { - return m_hid.getRightX(); - } - - /** - * Get the Y axis value of left side of the controller. - * - * @return the axis value. - */ - public double getLeftY() { - return m_hid.getLeftY(); - } - - /** - * Get the Y axis value of right side of the controller. - * - * @return the axis value. - */ - public double getRightY() { - return m_hid.getRightY(); - } - - /** - * Get the L2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as - * opposed to the usual [-1, 1]. - * - * @return the axis value. - */ - public double getL2Axis() { - return m_hid.getL2Axis(); - } - - /** - * Get the R2 axis value of the controller. Note that this axis is bound to the range of [0, 1] as - * opposed to the usual [-1, 1]. - * - * @return the axis value. - */ - public double getR2Axis() { - return m_hid.getR2Axis(); - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java deleted file mode 100644 index a3ac578f5b8..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ /dev/null @@ -1,405 +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 org.wpilib.commands3.button; - -import edu.wpi.first.wpilibj.StadiaController; -import org.wpilib.commands3.Scheduler; -import org.wpilib.commands3.Trigger; - -/** - * A version of {@link StadiaController} with {@link Trigger} factories for command-based. - * - * @see StadiaController - */ -@SuppressWarnings("MethodName") -public class CommandStadiaController extends CommandGenericHID { - private final StadiaController m_hid; - - /** - * Construct an instance of a controller. - * - * @param port The port index on the Driver Station that the controller is plugged into. - */ - public CommandStadiaController(int port) { - super(port); - m_hid = new StadiaController(port); - } - - /** - * Get the underlying GenericHID object. - * - * @return the wrapped GenericHID object - */ - @Override - public StadiaController getHID() { - return m_hid; - } - - /** - * Constructs an event instance around the left bumper's digital signal. - * - * @return an event instance representing the left bumper's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #leftBumper(EventLoop) - */ - public Trigger leftBumper() { - return leftBumper(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the left bumper's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the right bumper's digital signal attached to the given - * loop. - */ - public Trigger leftBumper(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftBumper(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the right bumper's digital signal. - * - * @return an event instance representing the right bumper's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #rightBumper(EventLoop) - */ - public Trigger rightBumper() { - return rightBumper(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the right bumper's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the left bumper's digital signal attached to the given - * loop. - */ - public Trigger rightBumper(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightBumper(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the left stick button's digital signal. - * - * @return an event instance representing the left stick button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #leftStick(EventLoop) - */ - public Trigger leftStick() { - return leftStick(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the left stick button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the left stick button's digital signal attached to the - * given loop. - */ - public Trigger leftStick(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftStick(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the right stick button's digital signal. - * - * @return an event instance representing the right stick button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #rightStick(EventLoop) - */ - public Trigger rightStick() { - return rightStick(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the right stick button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the right stick button's digital signal attached to the - * given loop. - */ - public Trigger rightStick(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightStick(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the right trigger button's digital signal. - * - * @return an event instance representing the right trigger button's digital signal attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #rightTrigger(EventLoop) - */ - public Trigger rightTrigger() { - return rightTrigger(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the right trigger button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the right trigger button's digital signal attached to - * the given loop. - */ - public Trigger rightTrigger(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightTrigger(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the left trigger button's digital signal. - * - * @return an event instance representing the left trigger button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #leftTrigger(EventLoop) - */ - public Trigger leftTrigger() { - return leftTrigger(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the left trigger button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the left trigger button's digital signal attached to the - * given loop. - */ - public Trigger leftTrigger(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftTrigger(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the A button's digital signal. - * - * @return an event instance representing the A button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #a(EventLoop) - */ - public Trigger a() { - return a(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the A button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the A button's digital signal attached to the given - * loop. - */ - public Trigger a(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.a(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the B button's digital signal. - * - * @return an event instance representing the B button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #b(EventLoop) - */ - public Trigger b() { - return b(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the B button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the B button's digital signal attached to the given - * loop. - */ - public Trigger b(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.b(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the X button's digital signal. - * - * @return an event instance representing the X button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #x(EventLoop) - */ - public Trigger x() { - return x(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the X button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the X button's digital signal attached to the given - * loop. - */ - public Trigger x(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.x(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the Y button's digital signal. - * - * @return an event instance representing the Y button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #y(EventLoop) - */ - public Trigger y() { - return y(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the Y button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the Y button's digital signal attached to the given - * loop. - */ - public Trigger y(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.y(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the ellipses button's digital signal. - * - * @return an event instance representing the ellipses button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #ellipses(EventLoop) - */ - public Trigger ellipses() { - return ellipses(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the ellipses button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the ellipses button's digital signal attached to the - * given loop. - */ - public Trigger ellipses(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.ellipses(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the stadia button's digital signal. - * - * @return an event instance representing the stadia button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #stadia(EventLoop) - */ - public Trigger stadia() { - return stadia(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the stadia button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the stadia button's digital signal attached to the given - * loop. - */ - public Trigger stadia(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.stadia(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the google button's digital signal. - * - * @return an event instance representing the google button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #google(EventLoop) - */ - public Trigger google() { - return google(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the google button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the google button's digital signal attached to the given - * loop. - */ - public Trigger google(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.google(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the frame button's digital signal. - * - * @return an event instance representing the frame button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #frame(EventLoop) - */ - public Trigger frame() { - return frame(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the frame button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the frame button's digital signal attached to the given - * loop. - */ - public Trigger frame(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.frame(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the hamburger button's digital signal. - * - * @return an event instance representing the hamburger button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #hamburger(EventLoop) - */ - public Trigger hamburger() { - return hamburger(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the hamburger button's digital signal. - * - * @param loop the event loop instance to attach the event to. - * @return an event instance representing the hamburger button's digital signal attached to the - * given loop. - */ - public Trigger hamburger(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.hamburger(scheduler.getDefaultEventLoop())); - } - - /** - * Get the X axis value of left side of the controller. - * - * @return The axis value. - */ - public double getLeftX() { - return m_hid.getLeftX(); - } - - /** - * Get the X axis value of right side of the controller. - * - * @return The axis value. - */ - public double getRightX() { - return m_hid.getRightX(); - } - - /** - * Get the Y axis value of left side of the controller. - * - * @return The axis value. - */ - public double getLeftY() { - return m_hid.getLeftY(); - } - - /** - * Get the Y axis value of right side of the controller. - * - * @return The axis value. - */ - public double getRightY() { - return m_hid.getRightY(); - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java deleted file mode 100644 index 0982cdfad0a..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ /dev/null @@ -1,393 +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 org.wpilib.commands3.button; - -import edu.wpi.first.wpilibj.XboxController; -import org.wpilib.commands3.Scheduler; -import org.wpilib.commands3.Trigger; - -/** - * A version of {@link XboxController} with {@link Trigger} factories for command-based. - * - * @see XboxController - */ -@SuppressWarnings("MethodName") -public class CommandXboxController extends CommandGenericHID { - private final XboxController m_hid; - - /** - * Construct an instance of a controller. - * - * @param port The port index on the Driver Station that the controller is plugged into. - */ - public CommandXboxController(int port) { - super(port); - m_hid = new XboxController(port); - } - - /** - * Get the underlying GenericHID object. - * - * @return the wrapped GenericHID object - */ - @Override - public XboxController getHID() { - return m_hid; - } - - /** - * Constructs an event instance around the left bumper's digital signal. - * - * @return an event instance representing the left bumper's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #leftBumper(Scheduler) - */ - public Trigger leftBumper() { - return leftBumper(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the left bumper's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the right bumper's digital signal attached to the given - * loop. - */ - public Trigger leftBumper(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftBumper(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the right bumper's digital signal. - * - * @return an event instance representing the right bumper's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #rightBumper(Scheduler) - */ - public Trigger rightBumper() { - return rightBumper(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the right bumper's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the left bumper's digital signal attached to the given - * loop. - */ - public Trigger rightBumper(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightBumper(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the left stick button's digital signal. - * - * @return an event instance representing the left stick button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #leftStick(Scheduler) - */ - public Trigger leftStick() { - return leftStick(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the left stick button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the left stick button's digital signal attached to the - * given loop. - */ - public Trigger leftStick(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftStick(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the right stick button's digital signal. - * - * @return an event instance representing the right stick button's digital signal attached to the - * {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #rightStick(Scheduler) - */ - public Trigger rightStick() { - return rightStick(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the right stick button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the right stick button's digital signal attached to the - * given loop. - */ - public Trigger rightStick(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightStick(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the A button's digital signal. - * - * @return an event instance representing the A button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #a(Scheduler) - */ - public Trigger a() { - return a(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the A button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the A button's digital signal attached to the given - * loop. - */ - public Trigger a(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.a(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the B button's digital signal. - * - * @return an event instance representing the B button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #b(Scheduler) - */ - public Trigger b() { - return b(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the B button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the B button's digital signal attached to the given - * loop. - */ - public Trigger b(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.b(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the X button's digital signal. - * - * @return an event instance representing the X button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #x(Scheduler) - */ - public Trigger x() { - return x(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the X button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the X button's digital signal attached to the given - * loop. - */ - public Trigger x(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.x(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the Y button's digital signal. - * - * @return an event instance representing the Y button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #y(Scheduler) - */ - public Trigger y() { - return y(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the Y button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the Y button's digital signal attached to the given - * loop. - */ - public Trigger y(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.y(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the start button's digital signal. - * - * @return an event instance representing the start button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #start(Scheduler) - */ - public Trigger start() { - return start(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the start button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the start button's digital signal attached to the given - * loop. - */ - public Trigger start(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.start(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs an event instance around the back button's digital signal. - * - * @return an event instance representing the back button's digital signal attached to the {@link - * Scheduler#getDefaultEventLoop() default scheduler button loop}. - * @see #back(Scheduler) - */ - public Trigger back() { - return back(Scheduler.getDefault()); - } - - /** - * Constructs an event instance around the back button's digital signal. - * - * @param scheduler the event loop instance to attach the event to. - * @return an event instance representing the back button's digital signal attached to the given - * loop. - */ - public Trigger back(Scheduler scheduler) { - return new Trigger(scheduler, m_hid.back(scheduler.getDefaultEventLoop())); - } - - /** - * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger - * will be true when the axis value is greater than {@code threshold}. - * - * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value - * should be in the range [0, 1] where 0 is the unpressed state of the axis. - * @param scheduler the event loop instance to attach the Trigger to. - * @return a Trigger instance that is true when the left trigger's axis exceeds the provided - * threshold, attached to the given event loop - */ - public Trigger leftTrigger(double threshold, Scheduler scheduler) { - return new Trigger(scheduler, m_hid.leftTrigger(threshold, scheduler.getDefaultEventLoop())); - } - - /** - * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger - * will be true when the axis value is greater than {@code threshold}. - * - * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value - * should be in the range [0, 1] where 0 is the unpressed state of the axis. - * @return a Trigger instance that is true when the left trigger's axis exceeds the provided - * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler button - * loop}. - */ - public Trigger leftTrigger(double threshold) { - return leftTrigger(threshold, Scheduler.getDefault()); - } - - /** - * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger - * will be true when the axis value is greater than 0.5. - * - * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger leftTrigger() { - return leftTrigger(0.5); - } - - /** - * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger - * will be true when the axis value is greater than {@code threshold}. - * - * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value - * should be in the range [0, 1] where 0 is the unpressed state of the axis. - * @param scheduler the event loop instance to attach the Trigger to. - * @return a Trigger instance that is true when the right trigger's axis exceeds the provided - * threshold, attached to the given event loop - */ - public Trigger rightTrigger(double threshold, Scheduler scheduler) { - return new Trigger(scheduler, m_hid.rightTrigger(threshold, scheduler.getDefaultEventLoop())); - } - - /** - * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger - * will be true when the axis value is greater than {@code threshold}. - * - * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value - * should be in the range [0, 1] where 0 is the unpressed state of the axis. - * @return a Trigger instance that is true when the right trigger's axis exceeds the provided - * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler button - * loop}. - */ - public Trigger rightTrigger(double threshold) { - return rightTrigger(threshold, Scheduler.getDefault()); - } - - /** - * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger - * will be true when the axis value is greater than 0.5. - * - * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. - */ - public Trigger rightTrigger() { - return rightTrigger(0.5); - } - - /** - * Get the X axis value of left side of the controller. - * - * @return The axis value. - */ - public double getLeftX() { - return m_hid.getLeftX(); - } - - /** - * Get the X axis value of right side of the controller. - * - * @return The axis value. - */ - public double getRightX() { - return m_hid.getRightX(); - } - - /** - * Get the Y axis value of left side of the controller. - * - * @return The axis value. - */ - public double getLeftY() { - return m_hid.getLeftY(); - } - - /** - * Get the Y axis value of right side of the controller. - * - * @return The axis value. - */ - public double getRightY() { - return m_hid.getRightY(); - } - - /** - * Get the left trigger (LT) axis value of the controller. Note that this axis is bound to the - * range of [0, 1] as opposed to the usual [-1, 1]. - * - * @return The axis value. - */ - public double getLeftTriggerAxis() { - return m_hid.getLeftTriggerAxis(); - } - - /** - * Get the right trigger (RT) axis value of the controller. Note that this axis is bound to the - * range of [0, 1] as opposed to the usual [-1, 1]. - * - * @return The axis value. - */ - public double getRightTriggerAxis() { - return m_hid.getRightTriggerAxis(); - } -} From caba87bbfc1a93243ff1c691d63cbbd561e7ea88 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 09:24:18 -0400 Subject: [PATCH 046/153] Adjust indentation on top-level command example snippet --- .../java/org/wpilib/commands3/Command.java | 72 +++++++++---------- 1 file changed, 36 insertions(+), 36 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index ccb3c2d90ee..a41ab920ae1 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -22,50 +22,50 @@ * loop. Failure to do so may result in an unrecoverable infinite loop. * *

{@snippet lang = java: - * // A 2013-style class-based command definition - * class ClassBasedCommand extends Command { - * public ClassBasedCommand(Subsystem requiredSubsystem) { - * addRequirements(requiredSubsystem); - * } + * // A 2013-style class-based command definition + * class ClassBasedCommand extends Command { + * public ClassBasedCommand(Subsystem requiredSubsystem) { + * addRequirements(requiredSubsystem); + * } * - * @Override - * public void initialize() {} + * @Override + * public void initialize() {} * - * @Override - * public void execute() {} + * @Override + * public void execute() {} * - * @Override - * public void end(boolean interrupted) {} + * @Override + * public void end(boolean interrupted) {} * - * @Override - * public void isFinished() { return true; } + * @Override + * public void isFinished() { return true; } * - * @Override - * public String getName() { return "The Command"; } - * } + * @Override + * public String getName() { return "The Command"; } + * } * - * Command command = new ClassBasedCommand(requiredSubsystem); + * Command command = new ClassBasedCommand(requiredSubsystem); * - * // Or a 2020-style function-based command - * Command command = requiredSubsystem - * .runOnce(() -> initialize()) - * .andThen( - * requiredSubsystem - * .run(() -> execute()) - * .until(() -> isFinished()) - * .onFinish(() -> end()) - * ).withName("The Command"); + * // Or a 2020-style function-based command + * Command command = requiredSubsystem + * .runOnce(() -> initialize()) + * .andThen( + * requiredSubsystem + * .run(() -> execute()) + * .until(() -> isFinished()) + * .onFinish(() -> end()) + * ).withName("The Command"); * - * // Can be represented with a 2025-style async-based definition - * Command command = requiredSubsystem.run((coroutine) -> { - * initialize(); - * while (!isFinished()) { - * coroutine.yield(); - * execute(); - * } - * end(); - * }).named("The Command"); - * } + * // Can be represented with a 2025-style async-based definition + * Command command = requiredSubsystem.run((coroutine) -> { + * initialize(); + * while (!isFinished()) { + * coroutine.yield(); + * execute(); + * } + * end(); + * }).named("The Command"); + * } */ public interface Command { /** The default command priority. */ From 70a7874038d97d06f9524cdddbc56c906f2b3199 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 10:11:04 -0400 Subject: [PATCH 047/153] Checkstyle test --- .../org/wpilib/commands3/CoroutineTest.java | 42 +- .../wpilib/commands3/ParallelGroupTest.java | 156 +++---- .../org/wpilib/commands3/SchedulerTest.java | 414 +++++++++--------- .../org/wpilib/commands3/SequenceTest.java | 62 +-- .../org/wpilib/commands3/TriggerTest.java | 98 +++-- 5 files changed, 398 insertions(+), 374 deletions(-) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index 1417a79b093..906a338e513 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -19,13 +19,13 @@ import org.junit.jupiter.api.Test; class CoroutineTest { - Scheduler scheduler; - ContinuationScope scope; + Scheduler m_scheduler; + ContinuationScope m_scope; @BeforeEach void setup() { - scheduler = new Scheduler(); - scope = new ContinuationScope("Test Scope"); + m_scheduler = new Scheduler(); + m_scope = new ContinuationScope("Test Scope"); RobotController.setTimeSource(() -> System.nanoTime() / 1000L); } @@ -40,11 +40,11 @@ void forkMany() { co.park(); }).named("Fork Many"); - scheduler.schedule(all); - scheduler.run(); - assertTrue(scheduler.isRunning(a)); - assertTrue(scheduler.isRunning(b)); - assertTrue(scheduler.isRunning(c)); + m_scheduler.schedule(all); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(a)); + assertTrue(m_scheduler.isRunning(b)); + assertTrue(m_scheduler.isRunning(c)); } @Test @@ -61,16 +61,16 @@ void yieldInSynchronizedBlock() { } }).named("Yield In Synchronized Block"); - scheduler.schedule(yieldInSynchronized); + m_scheduler.schedule(yieldInSynchronized); try { - scheduler.run(); + m_scheduler.run(); fail("Monitor pinned exception should have been thrown"); } catch (IllegalStateException expected) { assertEquals( - "Coroutine.yield() cannot be called inside a synchronized block or method. " + - "Consider using a Lock instead of synchronized, " + - "or rewrite your code to avoid locks and mutexes altogether.", + "Coroutine.yield() cannot be called inside a synchronized block or method. " + + "Consider using a Lock instead of synchronized, " + + "or rewrite your code to avoid locks and mutexes altogether.", expected.getMessage()); } } @@ -92,8 +92,8 @@ void yieldInLockBody() { } }).named("Increment In Lock Block"); - scheduler.schedule(yieldInLock); - scheduler.run(); + m_scheduler.schedule(yieldInLock); + m_scheduler.run(); assertEquals(1, i.get()); } @@ -105,8 +105,8 @@ void coroutineEscapingCommand() { escapeeCallback.set(co::yield); }).named("Bad Command"); - scheduler.schedule(badCommand); - scheduler.run(); + m_scheduler.schedule(badCommand); + m_scheduler.run(); try { escapeeCallback.get().run(); @@ -135,8 +135,8 @@ void awaitAnyCleansUp() { co.park(); // prevent exiting }).named("Command"); - scheduler.schedule(outer); - scheduler.run(); + m_scheduler.schedule(outer); + m_scheduler.run(); // Everything should have run... assertTrue(firstRan.get()); @@ -144,6 +144,6 @@ void awaitAnyCleansUp() { assertTrue(ranAfterAwait.get()); // But only the outer command should still be running; secondInner should have been cancelled - assertEquals(Set.of(outer), scheduler.getRunningCommands()); + assertEquals(Set.of(outer), m_scheduler.getRunningCommands()); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 9b35242caab..dfddcbbfb08 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -4,7 +4,9 @@ package org.wpilib.commands3; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; import java.util.List; import java.util.concurrent.atomic.AtomicInteger; @@ -12,24 +14,24 @@ import org.junit.jupiter.api.Test; class ParallelGroupTest { - private Scheduler scheduler; + private Scheduler m_scheduler; @BeforeEach void setup() { - scheduler = new Scheduler(); + m_scheduler = new Scheduler(); } @Test void parallelAll() { - var r1 = new RequireableResource("R1", scheduler); - var r2 = new RequireableResource("R2", scheduler); + var r1 = new RequireableResource("R1", m_scheduler); + var r2 = new RequireableResource("R2", m_scheduler); var c1Count = new AtomicInteger(0); var c2Count = new AtomicInteger(0); var c1 = r1.run( - (coroutine) -> { + coroutine -> { for (int i = 0; i < 5; i++) { coroutine.yield(); c1Count.incrementAndGet(); @@ -38,7 +40,7 @@ void parallelAll() { .named("C1"); var c2 = r2.run( - (coroutine) -> { + coroutine -> { for (int i = 0; i < 10; i++) { coroutine.yield(); c2Count.incrementAndGet(); @@ -47,38 +49,38 @@ void parallelAll() { .named("C2"); var parallel = new ParallelGroup("Parallel", List.of(c1, c2), List.of(c1, c2)); - scheduler.schedule(parallel); + m_scheduler.schedule(parallel); // First call to run() should schedule and start the commands - scheduler.run(); - assertTrue(scheduler.isRunning(parallel)); - assertTrue(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(parallel)); + assertTrue(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); // Next call to run() should start them for (int i = 1; i < 5; i++) { - scheduler.run(); - assertTrue(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); assertEquals(i, c1Count.get()); assertEquals(i, c2Count.get()); } // c1 should finish after 5 iterations; c2 should continue for another 5 for (int i = 5; i < 10; i++) { - scheduler.run(); - assertFalse(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); assertEquals(5, c1Count.get()); assertEquals(i, c2Count.get()); } // one final run() should unschedule the c2 command - scheduler.run(); - assertFalse(scheduler.isRunning(c1)); - assertFalse(scheduler.isRunning(c2)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(c1)); + assertFalse(m_scheduler.isRunning(c2)); // the next run should complete the group - scheduler.run(); - assertFalse(scheduler.isRunning(parallel)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(parallel)); // and final counts should be 5 and 10 assertEquals(5, c1Count.get()); @@ -87,15 +89,15 @@ void parallelAll() { @Test void race() { - var r1 = new RequireableResource("R1", scheduler); - var r2 = new RequireableResource("R2", scheduler); + var r1 = new RequireableResource("R1", m_scheduler); + var r2 = new RequireableResource("R2", m_scheduler); var c1Count = new AtomicInteger(0); var c2Count = new AtomicInteger(0); var c1 = r1.run( - (coroutine) -> { + coroutine -> { for (int i = 0; i < 5; i++) { coroutine.yield(); c1Count.incrementAndGet(); @@ -104,7 +106,7 @@ void race() { .named("C1"); var c2 = r2.run( - (coroutine) -> { + coroutine -> { for (int i = 0; i < 10; i++) { coroutine.yield(); c2Count.incrementAndGet(); @@ -113,29 +115,29 @@ void race() { .named("C2"); var race = new ParallelGroup("Race", List.of(c1, c2), List.of()); - scheduler.schedule(race); + m_scheduler.schedule(race); // First call to run() should schedule the commands - scheduler.run(); - assertTrue(scheduler.isRunning(race)); - assertTrue(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(race)); + assertTrue(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); for (int i = 1; i < 5; i++) { - scheduler.run(); - assertTrue(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); assertEquals(i, c1Count.get()); assertEquals(i, c2Count.get()); } - scheduler.run(); // complete c1 - assertTrue(scheduler.isRunning(race)); - assertFalse(scheduler.isRunning(c1)); - assertTrue(scheduler.isRunning(c2)); + m_scheduler.run(); // complete c1 + assertTrue(m_scheduler.isRunning(race)); + assertFalse(m_scheduler.isRunning(c1)); + assertTrue(m_scheduler.isRunning(c2)); - scheduler.run(); // complete parallel and cleanup - assertFalse(scheduler.isRunning(race)); - assertFalse(scheduler.isRunning(c2)); + m_scheduler.run(); // complete parallel and cleanup + assertFalse(m_scheduler.isRunning(race)); + assertFalse(m_scheduler.isRunning(c2)); // and final counts should be 5 and 5 assertEquals(5, c1Count.get()); @@ -144,14 +146,14 @@ void race() { @Test void nested() { - var resource = new RequireableResource("Resource", scheduler); + var resource = new RequireableResource("Resource", m_scheduler); var count = new AtomicInteger(0); var command = resource .run( - (coroutine) -> { + coroutine -> { for (int i = 0; i < 5; i++) { coroutine.yield(); count.incrementAndGet(); @@ -163,51 +165,51 @@ void nested() { var outer = ParallelGroup.all(inner).named("Outer"); // Scheduling: Outer group should be on deck - scheduler.schedule(outer); - assertTrue(scheduler.isScheduled(outer)); - assertFalse(scheduler.isScheduledOrRunning(inner)); - assertFalse(scheduler.isScheduledOrRunning(command)); + m_scheduler.schedule(outer); + assertTrue(m_scheduler.isScheduled(outer)); + assertFalse(m_scheduler.isScheduledOrRunning(inner)); + assertFalse(m_scheduler.isScheduledOrRunning(command)); // First run: Inner group and command should both be scheduled and running - scheduler.run(); - assertTrue(scheduler.isRunning(outer), "Outer group should be running"); - assertTrue(scheduler.isRunning(inner), "Inner group should be running"); - assertTrue(scheduler.isRunning(command), "Command should be running"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(m_scheduler.isRunning(inner), "Inner group should be running"); + assertTrue(m_scheduler.isRunning(command), "Command should be running"); assertEquals(0, count.get()); // Runs 2 through 5: Outer and inner should both be running while the command runs for (int i = 1; i < 5; i++) { - scheduler.run(); - assertTrue(scheduler.isRunning(outer), "Outer group should be running"); - assertTrue(scheduler.isRunning(inner), "Inner group should be running"); - assertTrue(scheduler.isRunning(command), "Command should be running (" + i + ")"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(m_scheduler.isRunning(inner), "Inner group should be running"); + assertTrue(m_scheduler.isRunning(command), "Command should be running (" + i + ")"); assertEquals(i, count.get()); } // Run 6: Command should have completed naturally - scheduler.run(); - assertTrue(scheduler.isRunning(outer), "Outer group should be running"); - assertTrue(scheduler.isRunning(inner), "Inner group should be running"); - assertFalse(scheduler.isRunning(command), "Command should have completed"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); + assertTrue(m_scheduler.isRunning(inner), "Inner group should be running"); + assertFalse(m_scheduler.isRunning(command), "Command should have completed"); // Run 7: Having seen the command complete, inner group should exit - scheduler.run(); - assertTrue(scheduler.isRunning(outer), "Outer group should be running"); - assertFalse(scheduler.isRunning(inner), "Inner group should have completed"); - assertFalse(scheduler.isRunning(command), "Command should have completed"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); + assertFalse(m_scheduler.isRunning(inner), "Inner group should have completed"); + assertFalse(m_scheduler.isRunning(command), "Command should have completed"); // Run 8: Having seen the inner group complete, outer group should now exit - scheduler.run(); - assertFalse(scheduler.isRunning(outer), "Outer group should be running"); - assertFalse(scheduler.isRunning(inner), "Inner group should have completed"); - assertFalse(scheduler.isRunning(command), "Command should have completed"); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(outer), "Outer group should be running"); + assertFalse(m_scheduler.isRunning(inner), "Inner group should have completed"); + assertFalse(m_scheduler.isRunning(command), "Command should have completed"); } @Test void automaticNameRace() { - var a = Command.noRequirements((coroutine) -> {}).named("A"); - var b = Command.noRequirements((coroutine) -> {}).named("B"); - var c = Command.noRequirements((coroutine) -> {}).named("C"); + var a = Command.noRequirements(coroutine -> {}).named("A"); + var b = Command.noRequirements(coroutine -> {}).named("B"); + var c = Command.noRequirements(coroutine -> {}).named("C"); var group = ParallelGroup.builder().optional(a, b, c).withAutomaticName(); assertEquals("(A | B | C)", group.name()); @@ -215,9 +217,9 @@ void automaticNameRace() { @Test void automaticNameAll() { - var a = Command.noRequirements((coroutine) -> {}).named("A"); - var b = Command.noRequirements((coroutine) -> {}).named("B"); - var c = Command.noRequirements((coroutine) -> {}).named("C"); + var a = Command.noRequirements(coroutine -> {}).named("A"); + var b = Command.noRequirements(coroutine -> {}).named("B"); + var c = Command.noRequirements(coroutine -> {}).named("C"); var group = ParallelGroup.builder().requiring(a, b, c).withAutomaticName(); assertEquals("(A & B & C)", group.name()); @@ -225,9 +227,9 @@ void automaticNameAll() { @Test void automaticNameDeadline() { - var a = Command.noRequirements((coroutine) -> {}).named("A"); - var b = Command.noRequirements((coroutine) -> {}).named("B"); - var c = Command.noRequirements((coroutine) -> {}).named("C"); + var a = Command.noRequirements(coroutine -> {}).named("A"); + var b = Command.noRequirements(coroutine -> {}).named("B"); + var c = Command.noRequirements(coroutine -> {}).named("C"); var group = ParallelGroup.builder().requiring(a).optional(b, c).withAutomaticName(); assertEquals("[(A) * (B | C)]", group.name()); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index db2f33c9c2b..eff742feccf 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -25,12 +25,12 @@ @Timeout(5) class SchedulerTest { - private Scheduler scheduler; + private Scheduler m_scheduler; @BeforeEach void setup() { RobotController.setTimeSource(() -> System.nanoTime() / 1000L); - scheduler = new Scheduler(); + m_scheduler = new Scheduler(); } @Test @@ -39,7 +39,7 @@ void basic() { var ran = new AtomicBoolean(false); var command = Command.noRequirements( - (coroutine) -> { + coroutine -> { do { coroutine.yield(); } while (!enabled.get()); @@ -47,13 +47,13 @@ void basic() { }) .named("Basic Command"); - scheduler.schedule(command); - scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command should be running after being scheduled"); + m_scheduler.schedule(command); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command), "Command should be running after being scheduled"); enabled.set(true); - scheduler.run(); - if (scheduler.isRunning(command)) { + m_scheduler.run(); + if (m_scheduler.isRunning(command)) { fail("Command should no longer be running after awaiting its completion"); } @@ -62,64 +62,65 @@ void basic() { @Test void higherPriorityCancels() { - var subsystem = new RequireableResource("Subsystem", scheduler); + final var subsystem = new RequireableResource("Subsystem", m_scheduler); - var lower = new PriorityCommand(-1000, subsystem); - var higher = new PriorityCommand(+1000, subsystem); + final var lower = new PriorityCommand(-1000, subsystem); + final var higher = new PriorityCommand(+1000, subsystem); - scheduler.schedule(lower); - scheduler.run(); - assertTrue(scheduler.isRunning(lower)); + m_scheduler.schedule(lower); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(lower)); - scheduler.schedule(higher); - scheduler.run(); - assertTrue(scheduler.isRunning(higher)); - assertFalse(scheduler.isRunning(lower)); + m_scheduler.schedule(higher); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(higher)); + assertFalse(m_scheduler.isRunning(lower)); } @Test void lowerPriorityDoesNotCancel() { - var subsystem = new RequireableResource("Subsystem", scheduler); + final var subsystem = new RequireableResource("Subsystem", m_scheduler); - var lower = new PriorityCommand(-1000, subsystem); - var higher = new PriorityCommand(+1000, subsystem); + final var lower = new PriorityCommand(-1000, subsystem); + final var higher = new PriorityCommand(+1000, subsystem); - scheduler.schedule(higher); - scheduler.run(); - assertTrue(scheduler.isRunning(higher)); + m_scheduler.schedule(higher); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(higher)); - scheduler.schedule(lower); - scheduler.run(); - if (!scheduler.isRunning(higher)) { + m_scheduler.schedule(lower); + m_scheduler.run(); + if (!m_scheduler.isRunning(higher)) { fail("Higher priority command should still be running"); } - if (scheduler.isRunning(lower)) { + if (m_scheduler.isRunning(lower)) { fail("Lower priority command should not be running"); } } @Test void samePriorityCancels() { - var subsystem = new RequireableResource("Subsystem", scheduler); + final var subsystem = new RequireableResource("Subsystem", m_scheduler); - var first = new PriorityCommand(512, subsystem); - var second = new PriorityCommand(512, subsystem); + final var first = new PriorityCommand(512, subsystem); + final var second = new PriorityCommand(512, subsystem); - scheduler.schedule(first); - scheduler.run(); - assertTrue(scheduler.isRunning(first)); + m_scheduler.schedule(first); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(first)); - scheduler.schedule(second); - scheduler.run(); - assertTrue(scheduler.isRunning(second), "New command should be running"); - assertFalse(scheduler.isRunning(first), "Old command should be canceled"); + m_scheduler.schedule(second); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(second), "New command should be running"); + assertFalse(m_scheduler.isRunning(first), "Old command should be canceled"); } @Test + @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void atomicity() { var resource = - new RequireableResource("X", scheduler) { - int x = 0; + new RequireableResource("X", m_scheduler) { + int m_x = 0; }; // Launch 100 commands that each call `x++` 500 times. @@ -132,42 +133,43 @@ void atomicity() { for (int cmdCount = 0; cmdCount < numCommands; cmdCount++) { var command = Command.noRequirements( - (coroutine) -> { + coroutine -> { for (int i = 0; i < iterations; i++) { coroutine.yield(); - resource.x++; + resource.m_x++; } }) .named("CountCommand[" + cmdCount + "]"); - scheduler.schedule(command); + m_scheduler.schedule(command); } for (int i = 0; i < iterations; i++) { - scheduler.run(); + m_scheduler.run(); } - scheduler.run(); + m_scheduler.run(); - assertEquals(numCommands * iterations, resource.x); + assertEquals(numCommands * iterations, resource.m_x); } @Test + @SuppressWarnings("PMD.AvoidCatchingGenericException") void errorDetection() { - var resource = new RequireableResource("X", scheduler); + var resource = new RequireableResource("X", m_scheduler); var command = resource .run( - (coroutine) -> { + coroutine -> { throw new RuntimeException("The exception"); }) .named("Bad Behavior"); - new Trigger(scheduler, () -> true) + new Trigger(m_scheduler, () -> true) .onTrue(command); try { - scheduler.run(); + m_scheduler.run(); fail("An exception should have been thrown"); } catch (RuntimeException e) { assertEquals("The exception", e.getMessage()); @@ -188,7 +190,7 @@ void errorDetection() { void nestedErrorDetection() { var command = Command.noRequirements(co -> { co.await(Command.noRequirements(c2 -> { - new Trigger(scheduler, () -> true) + new Trigger(m_scheduler, () -> true) .onTrue(Command.noRequirements(c3 -> { // Throws IndexOutOfBoundsException new ArrayList<>(0).get(-1); @@ -198,14 +200,14 @@ void nestedErrorDetection() { }).named("Schedules With Trigger")); }).named("Schedules Directly"); - scheduler.schedule(command); + m_scheduler.schedule(command); // The first run sets up the trigger, but does not fire // The second run will fire the trigger and cause the inner command to run and throw - scheduler.run(); + m_scheduler.run(); try { - scheduler.run(); + m_scheduler.run(); fail("Index OOB exception expected"); } catch (IndexOutOfBoundsException e) { StackTraceElement[] stackTrace = e.getStackTrace(); @@ -233,49 +235,50 @@ void nestedErrorDetection() { } @Test + @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void runResource() { var example = - new RequireableResource("Counting", scheduler) { - int x = 0; + new RequireableResource("Counting", m_scheduler) { + int m_x = 0; }; Command countToTen = example .run( - (coroutine) -> { - example.x = 0; + coroutine -> { + example.m_x = 0; for (int i = 0; i < 10; i++) { coroutine.yield(); - example.x++; + example.m_x++; } }) .named("Count To Ten"); - scheduler.schedule(countToTen); + m_scheduler.schedule(countToTen); for (int i = 0; i < 10; i++) { - scheduler.run(); + m_scheduler.run(); } - scheduler.run(); + m_scheduler.run(); - assertEquals(10, example.x); + assertEquals(10, example.m_x); } @Test void cancelOnInterruptDoesNotResume() { var count = new AtomicInteger(0); - var resource = new RequireableResource("Resource", scheduler); + var resource = new RequireableResource("Resource", m_scheduler); var interrupter = Command.requiring(resource) - .executing((coroutine) -> {}) + .executing(coroutine -> {}) .withPriority(2) .named("Interrupter"); var canceledCommand = Command.requiring(resource) .executing( - (coroutine) -> { + coroutine -> { count.set(1); coroutine.yield(); count.set(2); @@ -283,11 +286,11 @@ void cancelOnInterruptDoesNotResume() { .withPriority(1) .named("Cancel By Default"); - scheduler.schedule(canceledCommand); - scheduler.run(); + m_scheduler.schedule(canceledCommand); + m_scheduler.run(); - scheduler.schedule(interrupter); - scheduler.run(); + m_scheduler.schedule(interrupter); + m_scheduler.run(); assertEquals(1, count.get()); // the second "set" call should not have run } @@ -295,11 +298,11 @@ void cancelOnInterruptDoesNotResume() { void scheduleOverDefaultDoesNotRescheduleDefault() { var count = new AtomicInteger(0); - var resource = new RequireableResource("Resource", scheduler); + var resource = new RequireableResource("Resource", m_scheduler); var defaultCmd = resource .run( - (coroutine) -> { + coroutine -> { while (true) { count.incrementAndGet(); coroutine.yield(); @@ -308,18 +311,18 @@ void scheduleOverDefaultDoesNotRescheduleDefault() { .withPriority(-1) .named("Default Command"); - var newerCmd = resource.run((coroutine) -> {}).named("Newer Command"); + final var newerCmd = resource.run(coroutine -> {}).named("Newer Command"); resource.setDefaultCommand(defaultCmd); - scheduler.run(); - assertTrue(scheduler.isRunning(defaultCmd), "Default command should be running"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(defaultCmd), "Default command should be running"); - scheduler.schedule(newerCmd); - scheduler.run(); - assertFalse(scheduler.isRunning(defaultCmd), "Default command should have been interrupted"); + m_scheduler.schedule(newerCmd); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(defaultCmd), "Default command should have been interrupted"); assertEquals(1, count.get(), "Default command should have run once"); - scheduler.run(); - assertTrue(scheduler.isRunning(defaultCmd)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(defaultCmd)); } @Test @@ -328,11 +331,11 @@ void cancelAllCancelsAll() { for (int i = 1; i <= 10; i++) { commands.add(Command.noRequirements(Coroutine::yield).named("Command " + i)); } - commands.forEach(scheduler::schedule); - scheduler.run(); - scheduler.cancelAll(); + commands.forEach(m_scheduler::schedule); + m_scheduler.run(); + m_scheduler.cancelAll(); for (Command command : commands) { - if (scheduler.isRunning(command)) { + if (m_scheduler.isRunning(command)) { fail(command.name() + " was not canceled by cancelAll()"); } } @@ -342,34 +345,34 @@ void cancelAllCancelsAll() { void cancelAllStartsDefaults() { var resources = new ArrayList(10); for (int i = 1; i <= 10; i++) { - resources.add(new RequireableResource("System " + i, scheduler)); + resources.add(new RequireableResource("System " + i, m_scheduler)); } var command = new CommandBuilder().requiring(resources).executing(Coroutine::yield).named("Big Command"); // Scheduling the command should evict the on-deck default commands - scheduler.schedule(command); + m_scheduler.schedule(command); // Then running should get it into the set of running commands - scheduler.run(); + m_scheduler.run(); // Cancelling should clear out the set of running commands - scheduler.cancelAll(); + m_scheduler.cancelAll(); // Then ticking the scheduler once to fully remove the command and schedule the defaults - scheduler.run(); + m_scheduler.run(); // Then one more tick to start running the scheduled defaults - scheduler.run(); + m_scheduler.run(); - if (scheduler.isRunning(command)) { - System.err.println(scheduler.getRunningCommands()); + if (m_scheduler.isRunning(command)) { + System.err.println(m_scheduler.getRunningCommands()); fail(command.name() + " was not canceled by cancelAll()"); } for (var resource : resources) { - var runningCommands = scheduler.getRunningCommandsFor(resource); + var runningCommands = m_scheduler.getRunningCommandsFor(resource); assertEquals( 1, runningCommands.size(), @@ -385,13 +388,13 @@ void cancelAllStartsDefaults() { void cancelDeeplyNestedCompositions() { Command root = Command.noRequirements( - (co) -> { + co -> { co.await( Command.noRequirements( - (co2) -> { + co2 -> { co2.await( Command.noRequirements( - (co3) -> { + co3 -> { co3.await( Command.noRequirements(Coroutine::park) .named("Park")); @@ -402,27 +405,27 @@ void cancelDeeplyNestedCompositions() { }) .named("Root"); - scheduler.schedule(root); + m_scheduler.schedule(root); - scheduler.run(); - assertEquals(4, scheduler.getRunningCommands().size()); + m_scheduler.run(); + assertEquals(4, m_scheduler.getRunningCommands().size()); - scheduler.cancel(root); - assertEquals(0, scheduler.getRunningCommands().size()); + m_scheduler.cancel(root); + assertEquals(0, m_scheduler.getRunningCommands().size()); } @Test void compositionsDoNotSelfCancel() { - var res = new RequireableResource("The Resource", scheduler); + var res = new RequireableResource("The Resource", m_scheduler); var group = res.run( - (co) -> { + co -> { co.await( res.run( - (co2) -> { + co2 -> { co2.await( res.run( - (co3) -> { + co3 -> { co3.await(res.run(Coroutine::park).named("Park")); }) .named("C3")); @@ -431,72 +434,74 @@ void compositionsDoNotSelfCancel() { }) .named("Group"); - scheduler.schedule(group); - scheduler.run(); - assertEquals(4, scheduler.getRunningCommands().size()); - assertTrue(scheduler.isRunning(group)); + m_scheduler.schedule(group); + m_scheduler.run(); + assertEquals(4, m_scheduler.getRunningCommands().size()); + assertTrue(m_scheduler.isRunning(group)); } @Test void compositionsDoNotCancelParent() { - var res = new RequireableResource("The Resource", scheduler); + var res = new RequireableResource("The Resource", m_scheduler); var group = res.run(co -> { co.fork(res.run(Coroutine::park).named("First Child")); co.fork(res.run(Coroutine::park).named("Second Child")); co.park(); }).named("Group"); - scheduler.schedule(group); - scheduler.run(); + m_scheduler.schedule(group); + m_scheduler.run(); assertEquals( List.of("Group", "Second Child"), - scheduler.getRunningCommands().stream().map(Command::name).toList() + m_scheduler.getRunningCommands().stream().map(Command::name).toList() ); } @Test void compositionsDoNotNeedRequirements() { - var r1 = new RequireableResource("R1", scheduler); - var r2 = new RequireableResource("r2", scheduler); + var r1 = new RequireableResource("R1", m_scheduler); + var r2 = new RequireableResource("r2", m_scheduler); // the group has no requirements, but can schedule child commands that do var group = Command.noRequirements( - (co) -> { + co -> { co.awaitAll( r1.run(Coroutine::park).named("R1 Command"), r2.run(Coroutine::park).named("R2 Command")); }) .named("Composition"); - scheduler.schedule(group); - scheduler.run(); // start r1 and r2 commands - assertEquals(3, scheduler.getRunningCommands().size()); + m_scheduler.schedule(group); + m_scheduler.run(); // start r1 and r2 commands + assertEquals(3, m_scheduler.getRunningCommands().size()); } @Test + @SuppressWarnings("PMD.AvoidCatchingGenericException") void compositionsCannotAwaitConflictingCommands() { - var res = new RequireableResource("The Resource", scheduler); + var res = new RequireableResource("The Resource", m_scheduler); var group = Command.noRequirements( - (co) -> { + co -> { co.awaitAll( res.run(Coroutine::park).named("First"), res.run(Coroutine::park).named("Second")); }) .named("Group"); - scheduler.schedule(group); + m_scheduler.schedule(group); // Running should attempt to schedule multiple conflicting commands try { - scheduler.run(); + m_scheduler.run(); fail("An exception should have been thrown"); } catch (IllegalArgumentException iae) { assertEquals( - "Command Second requires resources that are already used by First. Both require The Resource", + "Command Second requires resources that are already used by First. " + + "Both require The Resource", iae.getMessage()); } catch (Exception e) { fail("Unexpected exception: " + e); @@ -507,12 +512,12 @@ void compositionsCannotAwaitConflictingCommands() { void doesNotRunOnCancelWhenInterruptingOnDeck() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); var interrupter = resource.run(Coroutine::yield).named("Interrupter"); - scheduler.schedule(cmd); - scheduler.schedule(interrupter); - scheduler.run(); + m_scheduler.schedule(cmd); + m_scheduler.schedule(interrupter); + m_scheduler.run(); assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); } @@ -521,12 +526,12 @@ void doesNotRunOnCancelWhenInterruptingOnDeck() { void doesNotRunOnCancelWhenCancellingOnDeck() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - scheduler.schedule(cmd); + m_scheduler.schedule(cmd); // cancelling before calling .run() - scheduler.cancel(cmd); - scheduler.run(); + m_scheduler.cancel(cmd); + m_scheduler.run(); assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); } @@ -535,13 +540,13 @@ void doesNotRunOnCancelWhenCancellingOnDeck() { void runsOnCancelWhenInterruptingCommand() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); var interrupter = resource.run(Coroutine::park).named("Interrupter"); - scheduler.schedule(cmd); - scheduler.run(); - scheduler.schedule(interrupter); - scheduler.run(); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.schedule(interrupter); + m_scheduler.run(); assertTrue(ran.get(), "onCancel should have run!"); } @@ -550,13 +555,13 @@ void runsOnCancelWhenInterruptingCommand() { void doesNotRunOnCancelWhenCompleting() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - scheduler.schedule(cmd); - scheduler.run(); - scheduler.run(); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.run(); - assertFalse(scheduler.isScheduledOrRunning(cmd)); + assertFalse(m_scheduler.isScheduledOrRunning(cmd)); assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); } @@ -564,11 +569,11 @@ void doesNotRunOnCancelWhenCompleting() { void runsOnCancelWhenCancelling() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - scheduler.schedule(cmd); - scheduler.run(); - scheduler.cancel(cmd); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.cancel(cmd); assertTrue(ran.get(), "onCancel should have run!"); } @@ -577,78 +582,80 @@ void runsOnCancelWhenCancelling() { void runsOnCancelWhenCancellingParent() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); var group = new Sequence("Seq", Collections.singletonList(cmd)); - scheduler.schedule(group); - scheduler.run(); - scheduler.cancel(group); + m_scheduler.schedule(group); + m_scheduler.run(); + m_scheduler.cancel(group); assertTrue(ran.get(), "onCancel should have run!"); } @Test void sideloadThrowingException() { - scheduler.sideload( + m_scheduler.sideload( co -> { throw new RuntimeException("Bang!"); }); // An exception raised in a sideload function should bubble up - assertEquals("Bang!", assertThrowsExactly(RuntimeException.class, scheduler::run).getMessage()); + assertEquals( + "Bang!", + assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); } @Test void nestedResources() { var superstructure = - new RequireableResource("Superstructure", scheduler) { - private final RequireableResource elevator = - new RequireableResource("Elevator", scheduler); - private final RequireableResource arm = new RequireableResource("Arm", scheduler); + new RequireableResource("Superstructure", m_scheduler) { + private final RequireableResource m_elevator = + new RequireableResource("Elevator", m_scheduler); + private final RequireableResource m_arm = new RequireableResource("Arm", m_scheduler); public Command superCommand() { return run(co -> { - co.await(elevator.run(Coroutine::park).named("Elevator Subcommand")); - co.await(arm.run(Coroutine::park).named("Arm Subcommand")); + co.await(m_elevator.run(Coroutine::park).named("Elevator Subcommand")); + co.await(m_arm.run(Coroutine::park).named("Arm Subcommand")); }) .named("Super Command"); } }; - scheduler.schedule(superstructure.superCommand()); - scheduler.run(); + m_scheduler.schedule(superstructure.superCommand()); + m_scheduler.run(); assertEquals( - List.of(superstructure.arm.getDefaultCommand()), - superstructure.arm.getRunningCommands(), + List.of(superstructure.m_arm.getDefaultCommand()), + superstructure.m_arm.getRunningCommands(), "Arm should only be running its default command"); // Scheduling something that requires an in-use inner resource cancels the outer command - scheduler.schedule(superstructure.elevator.run(Coroutine::park).named("Conflict")); + m_scheduler.schedule(superstructure.m_elevator.run(Coroutine::park).named("Conflict")); - scheduler.run(); // schedules the default superstructure command - scheduler.run(); // starts running the default superstructure command + m_scheduler.run(); // schedules the default superstructure command + m_scheduler.run(); // starts running the default superstructure command assertEquals(List.of(superstructure.getDefaultCommand()), superstructure.getRunningCommands()); } @Test void protobuf() { - var res = new RequireableResource("The Resource", scheduler); + var res = new RequireableResource("The Resource", m_scheduler); var parkCommand = res.run(Coroutine::park).named("Park"); - var c3Command = res.run((co) -> co.await(parkCommand)).named("C3"); - var c2Command = res.run((co) -> co.await(c3Command)).named("C2"); - var group = res.run((co) -> co.await(c2Command)).named("Group"); + var c3Command = res.run(co -> co.await(parkCommand)).named("C3"); + var c2Command = res.run(co -> co.await(c3Command)).named("C2"); + var group = res.run(co -> co.await(c2Command)).named("Group"); - scheduler.schedule(group); - scheduler.run(); + m_scheduler.schedule(group); + m_scheduler.run(); var scheduledCommand1 = Command.noRequirements(Coroutine::park).named("Command 1"); var scheduledCommand2 = Command.noRequirements(Coroutine::park).named("Command 2"); - scheduler.schedule(scheduledCommand1); - scheduler.schedule(scheduledCommand2); + m_scheduler.schedule(scheduledCommand1); + m_scheduler.schedule(scheduledCommand2); var message = Scheduler.proto.createMessage(); - Scheduler.proto.pack(message, scheduler); + Scheduler.proto.pack(message, m_scheduler); var messageJson = message.toString(); assertEquals( """ @@ -706,39 +713,39 @@ void protobuf() { }""" .formatted( // Scheduler data - scheduler.lastRuntimeMs(), + m_scheduler.lastRuntimeMs(), // On deck commands - scheduler.runId(scheduledCommand1), - scheduler.runId(scheduledCommand2), + m_scheduler.runId(scheduledCommand1), + m_scheduler.runId(scheduledCommand2), // Running commands - scheduler.lastCommandRuntimeMs(group), - scheduler.totalRuntimeMs(group), - scheduler.runId(group), // id + m_scheduler.lastCommandRuntimeMs(group), + m_scheduler.totalRuntimeMs(group), + m_scheduler.runId(group), // id // top-level command, no parent ID - scheduler.lastCommandRuntimeMs(c2Command), - scheduler.totalRuntimeMs(c2Command), - scheduler.runId(c2Command), // id - scheduler.runId(group), // parent + m_scheduler.lastCommandRuntimeMs(c2Command), + m_scheduler.totalRuntimeMs(c2Command), + m_scheduler.runId(c2Command), // id + m_scheduler.runId(group), // parent - scheduler.lastCommandRuntimeMs(c3Command), - scheduler.totalRuntimeMs(c3Command), - scheduler.runId(c3Command), // id - scheduler.runId(c2Command), // parent + m_scheduler.lastCommandRuntimeMs(c3Command), + m_scheduler.totalRuntimeMs(c3Command), + m_scheduler.runId(c3Command), // id + m_scheduler.runId(c2Command), // parent - scheduler.lastCommandRuntimeMs(parkCommand), - scheduler.totalRuntimeMs(parkCommand), - scheduler.runId(parkCommand), // id - scheduler.runId(c3Command) // parent + m_scheduler.lastCommandRuntimeMs(parkCommand), + m_scheduler.totalRuntimeMs(parkCommand), + m_scheduler.runId(parkCommand), // id + m_scheduler.runId(c3Command) // parent ), messageJson); } @Test void siblingsInCompositionCanShareRequirements() { - var resource = new RequireableResource("The Resource", scheduler); + var resource = new RequireableResource("The Resource", m_scheduler); var firstRan = new AtomicBoolean(false); var secondRan = new AtomicBoolean(false); @@ -758,20 +765,23 @@ void siblingsInCompositionCanShareRequirements() { co.park(); }).named("Group"); - scheduler.schedule(group); - scheduler.run(); + m_scheduler.schedule(group); + m_scheduler.run(); assertTrue(firstRan.get(), "First child should have run to a yield point"); assertTrue(secondRan.get(), "Second child should have run to a yield point"); - assertFalse(scheduler.isScheduledOrRunning(first), "First child should have been interrupted"); - assertTrue(scheduler.isRunning(second), "Second child should still be running"); - assertTrue(scheduler.isRunning(group), "Group should still be running"); + assertFalse( + m_scheduler.isScheduledOrRunning(first), + "First child should have been interrupted"); + assertTrue(m_scheduler.isRunning(second), "Second child should still be running"); + assertTrue(m_scheduler.isRunning(group), "Group should still be running"); } @Test void nestedOneShotCompositionsAllRunInOneCycle() { var runs = new AtomicInteger(0); - Supplier makeOneShot = () -> Command.noRequirements(_c -> runs.incrementAndGet()).named("One Shot"); + Supplier makeOneShot = + () -> Command.noRequirements(_c -> runs.incrementAndGet()).named("One Shot"); var command = Command.noRequirements(co -> { co.fork(makeOneShot.get()); co.fork(makeOneShot.get()); @@ -786,10 +796,10 @@ void nestedOneShotCompositionsAllRunInOneCycle() { }).named("2")); }).named("Command"); - scheduler.schedule(command); - scheduler.run(); + m_scheduler.schedule(command); + m_scheduler.run(); assertEquals(5, runs.get(), "All oneshot commands should have run"); - assertFalse(scheduler.isRunning(command), "Command should have exited after one cycle"); + assertFalse(m_scheduler.isRunning(command), "Command should have exited after one cycle"); } record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java index 3d1869cea76..2d0c356277f 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java @@ -12,11 +12,11 @@ import org.junit.jupiter.api.Test; class SequenceTest { - private Scheduler scheduler; + private Scheduler m_scheduler; @BeforeEach void setup() { - scheduler = new Scheduler(); + m_scheduler = new Scheduler(); } @Test @@ -24,22 +24,22 @@ void single() { var command = Command.noRequirements(Coroutine::yield).named("The Command"); var sequence = new Sequence("The Sequence", List.of(command)); - scheduler.schedule(sequence); + m_scheduler.schedule(sequence); // First run - the composed command is scheduled and starts - scheduler.run(); - assertTrue(scheduler.isRunning(sequence)); - assertTrue(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence)); + assertTrue(m_scheduler.isRunning(command)); // Second run - the composed command completes - scheduler.run(); - assertTrue(scheduler.isRunning(sequence)); - assertFalse(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence)); + assertFalse(m_scheduler.isRunning(command)); // Third run - sequence sees the composed command is done and completes - scheduler.run(); - assertFalse(scheduler.isRunning(sequence)); - assertFalse(scheduler.isRunning(command)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(sequence)); + assertFalse(m_scheduler.isRunning(command)); } @Test @@ -48,37 +48,37 @@ void twoCommands() { var c2 = Command.noRequirements(Coroutine::yield).named("C2"); var sequence = new Sequence("C1 > C2", List.of(c1, c2)); - scheduler.schedule(sequence); + m_scheduler.schedule(sequence); // First run - c1 is scheduled and starts - scheduler.run(); - assertTrue(scheduler.isRunning(sequence), "Sequence should be running"); - assertTrue(scheduler.isRunning(c1), "Starting the sequence should start the first command"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence), "Sequence should be running"); + assertTrue(m_scheduler.isRunning(c1), "Starting the sequence should start the first command"); assertFalse( - scheduler.isScheduledOrRunning(c2), + m_scheduler.isScheduledOrRunning(c2), "The second command should still be pending completion of the first command"); // Second run - c1 completes - scheduler.run(); - assertTrue(scheduler.isRunning(sequence)); - assertFalse(scheduler.isRunning(c1), "First command should have completed"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence)); + assertFalse(m_scheduler.isRunning(c1), "First command should have completed"); assertFalse( - scheduler.isScheduledOrRunning(c2), "Second command should not start in the same cycle"); + m_scheduler.isScheduledOrRunning(c2), "Second command should not start in the same cycle"); // Third run - c2 is scheduled and starts - scheduler.run(); - assertTrue(scheduler.isRunning(sequence)); - assertTrue(scheduler.isRunning(c2), "Second command should have started"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence)); + assertTrue(m_scheduler.isRunning(c2), "Second command should have started"); // Fourth run - c2 completes - scheduler.run(); - assertTrue(scheduler.isRunning(sequence)); - assertFalse(scheduler.isRunning(c2), "Second command should have completed"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(sequence)); + assertFalse(m_scheduler.isRunning(c2), "Second command should have completed"); // Fifth run - sequence completes - scheduler.run(); - assertFalse(scheduler.isRunning(sequence), "Sequence should have completed"); - assertFalse(scheduler.isRunning(c1), "First command should have stopped"); - assertFalse(scheduler.isRunning(c2), "Second command should have stopped"); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(sequence), "Sequence should have completed"); + assertFalse(m_scheduler.isRunning(c1), "First command should have stopped"); + assertFalse(m_scheduler.isRunning(c2), "Second command should have stopped"); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index 329efce55dd..b45a454c862 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -12,117 +12,129 @@ import org.junit.jupiter.api.Test; class TriggerTest { - private Scheduler scheduler; + private Scheduler m_scheduler; @BeforeEach void setup() { - scheduler = new Scheduler(); + m_scheduler = new Scheduler(); } @Test void onTrue() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.onTrue(command); signal.set(true); - scheduler.run(); + m_scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command was not scheduled on rising edge"); + assertTrue(m_scheduler.isRunning(command), "Command was not scheduled on rising edge"); signal.set(false); - scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command should still be running on falling edge"); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command), "Command should still be running on falling edge"); } @Test void onFalse() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.onFalse(command); - scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command should be scheduled when signal starts low"); + m_scheduler.run(); + assertTrue( + m_scheduler.isRunning(command), + "Command should be scheduled when signal starts low"); signal.set(true); - scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command should still be running rising falling edge"); + m_scheduler.run(); + assertTrue( + m_scheduler.isRunning(command), + "Command should still be running rising falling edge"); } @Test void whileTrue() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.whileTrue(command); signal.set(true); - scheduler.run(); + m_scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command was not scheduled on rising edge"); + assertTrue( + m_scheduler.isRunning(command), + "Command was not scheduled on rising edge"); signal.set(false); - scheduler.run(); - assertFalse(scheduler.isRunning(command), "Command should be cancelled on falling edge"); + m_scheduler.run(); + assertFalse( + m_scheduler.isRunning(command), + "Command should be cancelled on falling edge"); } @Test void whileFalse() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.whileFalse(command); - scheduler.run(); - assertTrue(scheduler.isRunning(command), "Command should be scheduled when signal starts low"); + m_scheduler.run(); + assertTrue( + m_scheduler.isRunning(command), + "Command should be scheduled when signal starts low"); signal.set(true); - scheduler.run(); - assertFalse(scheduler.isRunning(command), "Command should be cancelled on rising edge"); + m_scheduler.run(); + assertFalse( + m_scheduler.isRunning(command), + "Command should be cancelled on rising edge"); } @Test void toggleOnTrue() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.toggleOnTrue(command); - scheduler.run(); - assertFalse(scheduler.isRunning(command)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command)); signal.set(true); - scheduler.run(); - assertTrue(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); signal.set(false); - scheduler.run(); - assertTrue(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); signal.set(true); - scheduler.run(); - assertFalse(scheduler.isRunning(command)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command)); } @Test void toggleOnFalse() { var signal = new AtomicBoolean(false); - var trigger = new Trigger(scheduler, signal::get); + var trigger = new Trigger(m_scheduler, signal::get); var command = Command.noRequirements(Coroutine::park).named("Command"); trigger.toggleOnFalse(command); - scheduler.run(); - assertTrue(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); signal.set(true); - scheduler.run(); - assertTrue(scheduler.isRunning(command)); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); signal.set(false); - scheduler.run(); - assertFalse(scheduler.isRunning(command)); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command)); } @Test @@ -138,20 +150,20 @@ void commandScoping() { }).named("Inner"); var outer = Command.noRequirements(co -> { - new Trigger(scheduler, innerSignal::get).onTrue(inner); + new Trigger(m_scheduler, innerSignal::get).onTrue(inner); co.yield(); }).named("Outer"); - scheduler.schedule(outer); - scheduler.run(); + m_scheduler.schedule(outer); + m_scheduler.run(); assertFalse(innerRan.get(), "The bound command should not run before the signal is set"); innerSignal.set(true); - scheduler.run(); + m_scheduler.run(); assertTrue(innerRan.get(), "The nested trigger should have run the bound command"); innerRan.set(false); - scheduler.run(); + m_scheduler.run(); assertFalse(innerRan.get(), "Trigger should not have fired again"); } } From cca0acc7cd5bb1a39bed7e4cd5bdded3c268ada0 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 10:12:00 -0400 Subject: [PATCH 048/153] Suppress checkstyle for all generated protobuf files Instead of everything in a .proto package, which would also include handwritten code --- styleguide/checkstyle-suppressions.xml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/styleguide/checkstyle-suppressions.xml b/styleguide/checkstyle-suppressions.xml index 0ff41a1b98d..8254e2b6280 100644 --- a/styleguide/checkstyle-suppressions.xml +++ b/styleguide/checkstyle-suppressions.xml @@ -10,8 +10,9 @@ suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN" checks="(LocalVariableName|MemberName|MethodName|MethodTypeParameterName|ParameterName)" /> - + + From 162739d465d001b55bcc4dc0cf904d04579bbb2f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 16 Jun 2025 10:12:27 -0400 Subject: [PATCH 049/153] PMD --- .../java/org/wpilib/commands3/Command.java | 6 +--- .../org/wpilib/commands3/CommandBuilder.java | 2 +- .../org/wpilib/commands3/CommandState.java | 20 ++++++------ .../wpilib/commands3/CommandTraceHelper.java | 6 ++-- .../org/wpilib/commands3/Continuation.java | 32 ++++++++++++------- .../java/org/wpilib/commands3/Coroutine.java | 3 +- .../org/wpilib/commands3/ParallelGroup.java | 1 + .../commands3/ParallelGroupBuilder.java | 2 +- .../java/org/wpilib/commands3/Scheduler.java | 16 +++++++--- .../org/wpilib/commands3/SequenceBuilder.java | 2 +- .../java/org/wpilib/commands3/Trigger.java | 2 +- styleguide/pmd-ruleset.xml | 1 + 12 files changed, 53 insertions(+), 40 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index a41ab920ae1..3be3a9dcc0d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -140,11 +140,7 @@ default int priority() { * @return true if this command has a lower priority than the other one, false otherwise */ default boolean isLowerPriorityThan(Command other) { - if (other == null) { - return false; - } - - return priority() < other.priority(); + return other != null && priority() < other.priority(); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 0b6b51a56b7..6d905393dba 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -24,7 +24,7 @@ public class CommandBuilder { private Runnable m_onCancel = () -> {}; private String m_name; private int m_priority = Command.DEFAULT_PRIORITY; - private BooleanSupplier m_endCondition = null; + private BooleanSupplier m_endCondition; /** * Adds a resource as a requirement for the command. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index 7236636b8c7..ebde9ff624c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -10,9 +10,9 @@ final class CommandState { private final Command m_parent; private final Coroutine m_coroutine; private final Binding m_binding; - private double lastRuntimeMs = -1; - private double totalRuntimeMs = 0; - private final int id = System.identityHashCode(this); + private double m_lastRuntimeMs = -1; + private double m_totalRuntimeMs; + private final int m_id = System.identityHashCode(this); /** * Creates a new command state object. @@ -57,30 +57,30 @@ public Binding binding() { * @return The runtime, in milliseconds. */ public double lastRuntimeMs() { - return lastRuntimeMs; + return m_lastRuntimeMs; } public void setLastRuntimeMs(double lastRuntimeMs) { - this.lastRuntimeMs = lastRuntimeMs; - totalRuntimeMs += lastRuntimeMs; + this.m_lastRuntimeMs = lastRuntimeMs; + m_totalRuntimeMs += lastRuntimeMs; } public double totalRuntimeMs() { - return totalRuntimeMs; + return m_totalRuntimeMs; } public int id() { - return id; + return m_id; } @Override public boolean equals(Object obj) { - return obj instanceof CommandState that && this.id == that.id; + return obj instanceof CommandState that && this.m_id == that.m_id; } @Override public int hashCode() { - return id; + return m_id; } @Override diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java index 37d0f330bd9..a6bc7a33e91 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -55,7 +55,7 @@ public static StackTraceElement[] modifyTrace( boolean inTriggerInternals = frame.getClassName().equals(Trigger.class.getName()); boolean isScheduleCall = frame.getClassName().equals(Scheduler.class.getName()) - && frame.getMethodName().equals("schedule"); + && "schedule".equals(frame.getMethodName()); return inTriggerInternals || isScheduleCall; }) @@ -64,8 +64,8 @@ public static StackTraceElement[] modifyTrace( break; } - if (exceptionFrame.getClassName().equals("org.wpilib.commands3.Scheduler") - && exceptionFrame.getMethodName().equals("run")) { + if (exceptionFrame.getClassName().equals(Scheduler.class.getName()) + && "run".equals(exceptionFrame.getMethodName())) { sawRun = true; } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index bc51996d11f..8730b45a543 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -16,12 +16,13 @@ public final class Continuation { static final Class jdk_internal_vm_Continuation; private static final MethodHandle CONSTRUCTOR; + @SuppressWarnings("PMD.AvoidFieldNameMatchingMethodName") private static final MethodHandle YIELD; + @SuppressWarnings("PMD.AvoidFieldNameMatchingMethodName") private static final MethodHandle RUN; private static final MethodHandle IS_DONE; private static final MethodHandle java_lang_thread_setContinuation; - private static final MethodHandle java_lang_thread_getContinuation; private static final ThreadLocal mountedContinuation = new ThreadLocal<>(); @@ -66,11 +67,6 @@ public final class Continuation { Thread.class, "setContinuation", MethodType.methodType(void.class, Continuation.jdk_internal_vm_Continuation)); - - java_lang_thread_getContinuation = - lookup.findVirtual( - Thread.class, - "getContinuation", MethodType.methodType(Continuation.jdk_internal_vm_Continuation)); } catch (Throwable t) { throw new ExceptionInInitializerError(t); } @@ -84,10 +80,13 @@ public final class Continuation { * @param scope the continuation's scope, used in yield * @param target the continuation's body */ + @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public Continuation(ContinuationScope scope, Runnable target) { try { m_continuation = CONSTRUCTOR.invoke(scope.m_continuationScope, target); m_scope = scope; + } catch (RuntimeException | Error e) { + throw e; } catch (Throwable t) { throw new RuntimeException(t); } @@ -99,31 +98,31 @@ public Continuation(ContinuationScope scope, Runnable target) { * @return {@code true} for success; {@code false} for failure * @throws IllegalStateException if not currently in this continuation's scope */ + @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public boolean yield() { try { return (boolean) YIELD.invoke(m_scope.m_continuationScope); } catch (RuntimeException e) { throw e; } catch (Throwable t) { - throw new RuntimeException(t); + throw new Error(t); } } /** * Mounts and runs the continuation body. If suspended, continues it from the last suspend point. */ + @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public void run() { try { RUN.invoke(m_continuation); } catch (WrongMethodTypeException | ClassCastException e) { throw new IllegalStateException("Unable to run the underlying continuation!", e); - } catch (RuntimeException e) { + } catch (RuntimeException | Error e) { // The bound task threw an exception; re-throw it throw e; } catch (Throwable t) { - // Other error type (eg StackOverflowError, OutOfMemoryError), wrap in an Error so it won't - // be caught by a naive `catch (Exception e)` statement - throw new Error(t); + throw new RuntimeException(t); } } @@ -132,9 +131,12 @@ public void run() { * * @return whether this continuation is completed */ + @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public boolean isDone() { try { return (boolean) IS_DONE.invoke(m_continuation); + } catch (RuntimeException | Error e) { + throw e; } catch (Throwable t) { throw new RuntimeException(t); } @@ -146,20 +148,25 @@ public boolean isDone() { * * @param continuation the continuation to mount */ + @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public static void mountContinuation(Continuation continuation) { try { if (continuation == null) { java_lang_thread_setContinuation.invoke(Thread.currentThread(), null); mountedContinuation.remove(); } else { - java_lang_thread_setContinuation.invoke(Thread.currentThread(), continuation.m_continuation); + java_lang_thread_setContinuation.invoke( + Thread.currentThread(), continuation.m_continuation); mountedContinuation.set(continuation); } + } catch (RuntimeException | Error e) { + throw e; } catch (Throwable t) { // `t` is anything thrown internally by Thread.setContinuation. // It only assigns to a field, no way to throw // However, if the invocation fails for some reason, we'll end up with an // IllegalStateException when attempting to run an unmounted continuation + throw new RuntimeException(t); } } @@ -179,6 +186,7 @@ public String toString() { } + @SuppressWarnings("PMD.CompareObjectsWithEquals") boolean isMounted() { return this == getMountedContinuation(); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index d59f86da7dd..4c65ca05997 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -44,7 +44,7 @@ public boolean yield() { try { return m_backingContinuation.yield(); } catch (IllegalStateException e) { - if (e.getMessage().equals("Pinned: MONITOR")) { + if ("Pinned: MONITOR".equals(e.getMessage())) { // Yielding inside a synchronized block or method // Throw with an error message that's more helpful for our users throw new IllegalStateException( @@ -206,6 +206,7 @@ public void awaitAny(Command... commands) { * @throws IllegalArgumentException If at least one pair of commands is found in the input * where both commands have at least one required resource in common */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") private static void validateNoConflicts(Collection commands) { for (var c1 : commands) { for (var c2 : commands) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 90999c2fad3..e33cb39cf24 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -32,6 +32,7 @@ public class ParallelGroup implements Command { * @param requiredCommands The commands that are required to completed for the group to finish. If * this is empty, then the group will finish when any command in it has completed. */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") public ParallelGroup( String name, Collection allCommands, Collection requiredCommands) { requireNonNullParam(name, "name", "ParallelGroup"); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index b9aa4d7a7af..8ab0fe86c98 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -19,7 +19,7 @@ public class ParallelGroupBuilder { private final Set m_commands = new LinkedHashSet<>(); private final Set m_requiredCommands = new LinkedHashSet<>(); - private BooleanSupplier m_endCondition = null; + private BooleanSupplier m_endCondition; /** * Adds one or more optional commands to the group. They will not be required to complete for diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index db7c54c4b58..177638bbefc 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -284,6 +284,7 @@ private void evictConflictingOnDeckCommands(Command command) { * Cancels all running commands with which an incoming state conflicts. Ancestor commands of the * incoming state will not be canceled. */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") private void evictConflictingRunningCommands(CommandState incomingState) { // The set of root states with which the incoming state conflicts but does not inherit from Set conflictingRootStates = @@ -318,6 +319,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { * @param ancestor the potential ancestor for which to search * @return true if {@code ancestor} is the direct parent or indirect ancestor, false if not */ + @SuppressWarnings({"PMD.CompareObjectsWithEquals", "PMD.SimplifyBooleanReturns"}) private boolean inheritsFrom(CommandState state, Command ancestor) { if (state.parent() == null) { // No parent, cannot inherit @@ -346,6 +348,7 @@ private boolean inheritsFrom(CommandState state, Command ancestor) { * * @param command the command to cancel */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") public void cancel(Command command) { boolean running = isRunning(command); @@ -429,6 +432,7 @@ private void runCommands() { } } + @SuppressWarnings("PMD.AvoidCatchingGenericException") private void runCommand(CommandState state) { final var command = state.command(); final var coroutine = state.coroutine(); @@ -457,7 +461,7 @@ private void runCommand(CommandState state) { double elapsedMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); state.setLastRuntimeMs(elapsedMs); - if (currentState() == state) { + if (state.equals(currentState())) { // Remove the command we just ran from the top of the stack m_executingCommands.pop(); } @@ -516,12 +520,11 @@ private void scheduleDefaultCommands() { m_defaultCommands.forEach( (resource, defaultCommand) -> { if (m_commandStates.keySet().stream().noneMatch(c -> c.requires(resource)) - && m_onDeck.stream().noneMatch(c -> c.command().requires(resource))) { + && m_onDeck.stream().noneMatch(c -> c.command().requires(resource)) + && defaultCommand != null) { // Nothing currently running or scheduled // Schedule the resource's default command, if it has one - if (defaultCommand != null) { - schedule(defaultCommand); - } + schedule(defaultCommand); } }); } @@ -532,6 +535,7 @@ private void scheduleDefaultCommands() { * * @param parent the root command whose descendants to remove from the scheduler */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") private void removeOrphanedChildren(Command parent) { m_commandStates.entrySet().stream() .filter(e -> e.getValue().parent() == parent) @@ -566,6 +570,7 @@ public boolean isRunning(Command command) { * @param command the command to check * @return true if the command is scheduled to run, false if not */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") public boolean isScheduled(Command command) { return m_onDeck.stream().anyMatch(state -> state.command() == command); } @@ -684,6 +689,7 @@ public double totalRuntimeMs(Command command) { * @param command The command to get the run ID for * @return The run of the command */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") public int runId(Command command) { if (m_commandStates.containsKey(command)) { return m_commandStates.get(command).id(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index 2ef460f3c13..d7c592032db 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -18,7 +18,7 @@ */ public class SequenceBuilder { private final List m_steps = new ArrayList<>(); - private BooleanSupplier m_endCondition = null; + private BooleanSupplier m_endCondition; /** * Adds a command to the sequence. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 038a11ad20b..b16c3ef3904 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -29,7 +29,7 @@ public class Trigger implements BooleanSupplier { private final BooleanSupplier m_condition; private final EventLoop m_loop; private final Scheduler m_scheduler; - private Signal m_previousSignal = null; + private Signal m_previousSignal; private final Map> m_bindings = new EnumMap<>(BindingType.class); private final Runnable m_eventLoopCallback = this::poll; diff --git a/styleguide/pmd-ruleset.xml b/styleguide/pmd-ruleset.xml index 8553506b6fe..0c95363964d 100644 --- a/styleguide/pmd-ruleset.xml +++ b/styleguide/pmd-ruleset.xml @@ -9,6 +9,7 @@ .*/*JNI.* .*/*IntegrationTests.* .*/math/proto.* + .*/commands3/proto.* From 3aaaa8cc2017208d24980603769e9af5592d18c2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 18:59:21 -0400 Subject: [PATCH 050/153] Linting --- .../java/org/wpilib/commands3/Binding.java | 11 +- .../org/wpilib/commands3/BindingScope.java | 8 +- .../org/wpilib/commands3/BindingType.java | 16 +- .../org/wpilib/commands3/CommandBuilder.java | 69 +++++---- .../wpilib/commands3/CommandTraceHelper.java | 42 +++--- .../org/wpilib/commands3/Continuation.java | 4 +- .../wpilib/commands3/ContinuationScope.java | 1 + .../java/org/wpilib/commands3/Coroutine.java | 45 ++---- .../commands3/ParallelGroupBuilder.java | 25 ++- .../wpilib/commands3/RequireableResource.java | 21 +-- .../java/org/wpilib/commands3/Scheduler.java | 16 +- .../org/wpilib/commands3/SchedulerEvent.java | 70 ++++----- .../java/org/wpilib/commands3/Sequence.java | 2 +- .../org/wpilib/commands3/SequenceBuilder.java | 16 +- .../java/org/wpilib/commands3/Trigger.java | 50 +++--- .../commands3/button/CommandGenericHID.java | 67 ++++----- .../wpilib/commands3/button/POVButton.java | 5 +- .../wpilib/commands3/proto/CommandProto.java | 3 +- .../org/wpilib/commands3/CoroutineTest.java | 94 +++++++----- .../org/wpilib/commands3/SchedulerTest.java | 142 ++++++++++-------- .../org/wpilib/commands3/TriggerTest.java | 49 +++--- styleguide/spotbugs-exclude.xml | 15 ++ 22 files changed, 392 insertions(+), 379 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java index a2495de442b..41879e991c8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java @@ -13,15 +13,10 @@ * @param type The type of binding; or, when the bound command should run * @param command The bound command. Cannot be null. * @param frames The stack frames when the binding was created. Used for telemetry and error - * reporting so if a command throws an exception, we can tell users where that - * command was bound instead of giving a fairly useless backtrace of the command - * framework. + * reporting so if a command throws an exception, we can tell users where that command was bound + * instead of giving a fairly useless backtrace of the command framework. */ -record Binding( - BindingScope scope, - BindingType type, - Command command, - StackTraceElement[] frames) { +record Binding(BindingScope scope, BindingType type, Command command, StackTraceElement[] frames) { public Binding { ErrorMessages.requireNonNullParam(scope, "scope", "Binding"); ErrorMessages.requireNonNullParam(type, "type", "Binding"); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java index 5f70c3aabe1..2aea39d2caa 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java @@ -24,9 +24,7 @@ static BindingScope forCommand(Scheduler scheduler, Command command) { return new ForCommand(scheduler, command); } - /** - * A global binding scope. Bindings in this scope are always active. - */ + /** A global binding scope. Bindings in this scope are always active. */ final class Global implements BindingScope { // No reason not to be a singleton. public static final Global INSTANCE = new Global(); @@ -38,8 +36,8 @@ public boolean active() { } /** - * A binding scoped to the lifetime of a specific command. This should be used when a binding - * is created within a command, tying the lifetime of the binding to the declaring command. + * A binding scoped to the lifetime of a specific command. This should be used when a binding is + * created within a command, tying the lifetime of the binding to the declaring command. * * @param scheduler The scheduler managing the command. * @param command The command being scoped to. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java index 7845cc0952f..525d4bb56e5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java @@ -4,9 +4,7 @@ package org.wpilib.commands3; -/** - * Describes when a command bound to a trigger should run. - */ +/** Describes when a command bound to a trigger should run. */ enum BindingType { /** * An immediate or manual binding created when calling {@link Scheduler#schedule(Command)} @@ -14,8 +12,8 @@ enum BindingType { */ IMMEDIATE, /** - * Schedules (forks) a command on a rising edge signal. The command will run until it completes - * or is interrupted by another command requiring the same resources. + * Schedules (forks) a command on a rising edge signal. The command will run until it completes or + * is interrupted by another command requiring the same resources. */ SCHEDULE_ON_RISING_EDGE, /** @@ -35,14 +33,14 @@ enum BindingType { TOGGLE_ON_FALLING_EDGE, /** * Schedules a command on a rising edge signal. If the command is still running on the next - * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which - * would allow it to continue to run. + * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which would + * allow it to continue to run. */ RUN_WHILE_HIGH, /** * Schedules a command on a falling edge signal. If the command is still running on the next - * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which - * would allow it to continue to run. + * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which would + * allow it to continue to run. */ RUN_WHILE_LOW } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index 6d905393dba..f1a9816b57d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -149,8 +149,9 @@ public CommandBuilder whenCanceled(Runnable onCancel) { } /** - * Makes the command run until some end condition is met, if it hasn't already finished by then - * on its own. + * Makes the command run until some end condition is met, if it hasn't already finished by then on + * its own. + * * @param endCondition The hard end condition for the command. * @return The builder object, for chaining. */ @@ -161,6 +162,7 @@ public CommandBuilder until(BooleanSupplier endCondition) { /** * Makes the command run while some condition is true, ending when the condition becomes inactive. + * * @param active The command active condition. * @return The builder object, for chaining. */ @@ -179,37 +181,38 @@ public Command make() { Objects.requireNonNull(m_name, "Name was not specified"); Objects.requireNonNull(m_impl, "Command logic was not specified"); - var command = new Command() { - @Override - public void run(Coroutine coroutine) { - m_impl.accept(coroutine); - } - - @Override - public void onCancel() { - m_onCancel.run(); - } - - @Override - public String name() { - return m_name; - } - - @Override - public Set requirements() { - return m_requirements; - } - - @Override - public int priority() { - return m_priority; - } - - @Override - public String toString() { - return m_name; - } - }; + var command = + new Command() { + @Override + public void run(Coroutine coroutine) { + m_impl.accept(coroutine); + } + + @Override + public void onCancel() { + m_onCancel.run(); + } + + @Override + public String name() { + return m_name; + } + + @Override + public Set requirements() { + return m_requirements; + } + + @Override + public int priority() { + return m_priority; + } + + @Override + public String toString() { + return m_name; + } + }; if (m_endCondition == null) { // No custom end condition, just return the raw command diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java index a6bc7a33e91..4b0d3b17189 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -14,25 +14,24 @@ private CommandTraceHelper() { } /** - * Creates a modified stack trace where the trace of the scheduling code replaces the trace of - * the internal scheduler logic. + * Creates a modified stack trace where the trace of the scheduling code replaces the trace of the + * internal scheduler logic. * * @param commandExceptionTrace The trace of the exception raised during command execution. * @param commandScheduleTrace The trace of when the command was scheduled. * @return A new array of stack trace elements. */ public static StackTraceElement[] modifyTrace( - StackTraceElement[] commandExceptionTrace, - StackTraceElement[] commandScheduleTrace) { + StackTraceElement[] commandExceptionTrace, StackTraceElement[] commandScheduleTrace) { List frames = new ArrayList<>(); - List filteredClasses = List.of( - Coroutine.class.getName(), - Continuation.class.getName(), - Scheduler.class.getName(), - "org.wpilib.commands3.CommandBuilder$1", - "jdk.internal.vm.Continuation" - ); + List filteredClasses = + List.of( + Coroutine.class.getName(), + Continuation.class.getName(), + Scheduler.class.getName(), + "org.wpilib.commands3.CommandBuilder$1", + "jdk.internal.vm.Continuation"); boolean sawRun = false; for (var exceptionFrame : commandExceptionTrace) { @@ -44,28 +43,27 @@ public static StackTraceElement[] modifyTrace( if (sawRun) { // Inject a marker frame just so there's a distinction between the command's code and the // code that scheduled it, since they occur asynchronously - frames.add( - new StackTraceElement("=== Command Binding Trace ===", "", "", -1) - ); + frames.add(new StackTraceElement("=== Command Binding Trace ===", "", "", -1)); // Drop internal trigger frames, since they're not helpful for users. // The first frame here should be the line of user code that bound the command to a trigger. Stream.of(commandScheduleTrace) - .dropWhile(frame -> { - boolean inTriggerInternals = frame.getClassName().equals(Trigger.class.getName()); - boolean isScheduleCall = - frame.getClassName().equals(Scheduler.class.getName()) - && "schedule".equals(frame.getMethodName()); + .dropWhile( + frame -> { + boolean inTriggerInternals = frame.getClassName().equals(Trigger.class.getName()); + boolean isScheduleCall = + frame.getClassName().equals(Scheduler.class.getName()) + && "schedule".equals(frame.getMethodName()); - return inTriggerInternals || isScheduleCall; - }) + return inTriggerInternals || isScheduleCall; + }) .filter(frame -> !filteredClasses.contains(frame.getClassName())) .forEach(frames::add); break; } if (exceptionFrame.getClassName().equals(Scheduler.class.getName()) - && "run".equals(exceptionFrame.getMethodName())) { + && "run".equals(exceptionFrame.getMethodName())) { sawRun = true; } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 8730b45a543..7445a924897 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -16,10 +16,13 @@ public final class Continuation { static final Class jdk_internal_vm_Continuation; private static final MethodHandle CONSTRUCTOR; + @SuppressWarnings("PMD.AvoidFieldNameMatchingMethodName") private static final MethodHandle YIELD; + @SuppressWarnings("PMD.AvoidFieldNameMatchingMethodName") private static final MethodHandle RUN; + private static final MethodHandle IS_DONE; private static final MethodHandle java_lang_thread_setContinuation; @@ -185,7 +188,6 @@ public String toString() { return m_continuation.toString(); } - @SuppressWarnings("PMD.CompareObjectsWithEquals") boolean isMounted() { return this == getMountedContinuation(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index 46720ee4318..cd45d20c61b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -33,6 +33,7 @@ public final class ContinuationScope { /** * Constructs a new scope. + * * @param name The scope's name */ public ContinuationScope(String name) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 4c65ca05997..97227921848 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -25,7 +25,7 @@ public final class Coroutine { * @param scheduler The scheduler running the coroutine * @param scope The continuation scope the coroutine's backing continuation runs in * @param callback The callback for the continuation to execute when mounted. Often a command - * function's body. + * function's body. */ Coroutine(Scheduler scheduler, ContinuationScope scope, Consumer callback) { m_scheduler = scheduler; @@ -51,8 +51,7 @@ public boolean yield() { "Coroutine.yield() cannot be called inside a synchronized block or method. " + "Consider using a Lock instead of synchronized, " + "or rewrite your code to avoid locks and mutexes altogether.", - e - ); + e); } else { // rethrow throw e; @@ -75,21 +74,13 @@ public void park() { } /** - * Forks off a command. It will run until its natural completion, the parent command exits, - * or the parent command cancels it. The parent command will continue executing while the - * forked command runs, and can resync with the forked command using {@link #await(Command)}. + * Forks off a command. It will run until its natural completion, the parent command exits, or the + * parent command cancels it. The parent command will continue executing while the forked command + * runs, and can resync with the forked command using {@link #await(Command)}. * - *

{@snippet lang = java: - * Command example() { - * return Command.noRequirements((coroutine) -> { - * Command inner = ...; - * coroutine.fork(inner); - * // ... do more things - * // then sync back up with the inner command - * coroutine.await(inner); - * }).named("Example"); - * } - * } + *

{@snippet lang = java: Command example() { return Command.noRequirements((coroutine) -> { + * Command inner = ...; coroutine.fork(inner); // ... do more things // then sync back up with the + * inner command coroutine.await(inner); }).named("Example"); } } * * @param commands The commands to fork. */ @@ -203,8 +194,8 @@ public void awaitAny(Command... commands) { * a conflict is detected. * * @param commands The commands to validate - * @throws IllegalArgumentException If at least one pair of commands is found in the input - * where both commands have at least one required resource in common + * @throws IllegalArgumentException If at least one pair of commands is found in the input where + * both commands have at least one required resource in common */ @SuppressWarnings("PMD.CompareObjectsWithEquals") private static void validateNoConflicts(Collection commands) { @@ -225,8 +216,7 @@ private static void validateNoConflicts(Collection commands) { throw new IllegalArgumentException( "Command %s requires resources that are already used by %s. Both require %s" - .formatted(c2.name(), c1.name(), conflictNames) - ); + .formatted(c2.name(), c1.name(), conflictNames)); } } } @@ -238,15 +228,9 @@ private static void validateNoConflicts(Collection commands) { * *

For example, a basic autonomous routine that drives straight for 5 seconds: * - * {@snippet lang = java : - * Command timedDrive() { - * return drivebase.run((coroutine) -> { - * drivebase.tankDrive(1, 1); - * coroutine.wait(Seconds.of(5)); - * drivebase.stop(); - * }).named("Timed Drive"); - * } - * } + *

{@snippet lang = java : Command timedDrive() { return drivebase.run((coroutine) -> { + * drivebase.tankDrive(1, 1); coroutine.wait(Seconds.of(5)); drivebase.stop(); }).named("Timed + * Drive"); } } * * @param duration the duration of time to wait */ @@ -258,6 +242,7 @@ public void wait(Time duration) { /** * Yields until a condition is met. + * * @param condition The condition to wait for */ public void waitUntil(BooleanSupplier condition) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 8ab0fe86c98..b4247b861a4 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -11,10 +11,9 @@ import java.util.stream.Collectors; /** - * A builder class to configure and then create a {@link ParallelGroup}. Like - * {@link CommandBuilder}, the final command is created by calling the terminal - * {@link #named(String)} method, or with an automatically generated name using - * {@link #withAutomaticName()}. + * A builder class to configure and then create a {@link ParallelGroup}. Like {@link + * CommandBuilder}, the final command is created by calling the terminal {@link #named(String)} + * method, or with an automatically generated name using {@link #withAutomaticName()}. */ public class ParallelGroupBuilder { private final Set m_commands = new LinkedHashSet<>(); @@ -22,8 +21,8 @@ public class ParallelGroupBuilder { private BooleanSupplier m_endCondition; /** - * Adds one or more optional commands to the group. They will not be required to complete for - * the parallel group to exit, and will be canceled once all required commands have finished. + * Adds one or more optional commands to the group. They will not be required to complete for the + * parallel group to exit, and will be canceled once all required commands have finished. * * @param commands The optional commands to add to the group * @return The builder object, for chaining @@ -59,8 +58,8 @@ public ParallelGroupBuilder alongWith(Command command) { } /** - * Forces the group to be a pure race, where the group will finish after the first command in - * the group completes. All other commands in the group will be canceled. + * Forces the group to be a pure race, where the group will finish after the first command in the + * group completes. All other commands in the group will be canceled. * * @return The builder object, for chaining */ @@ -83,9 +82,9 @@ public ParallelGroupBuilder requireAll() { /** * Adds an end condition to the command group. If this condition is met before all required - * commands have completed, the group will exit early. If multiple end conditions are added - * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end - * condition added will be used and any previously configured condition will be overridden. + * commands have completed, the group will exit early. If multiple end conditions are added (e.g. + * {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end condition + * added will be used and any previously configured condition will be overridden. * * @param condition The end condition for the group * @return The builder object, for chaining @@ -112,8 +111,8 @@ public ParallelGroup named(String name) { // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(group, Command.waitUntil(m_endCondition).named("Until Condition")) - .named(name); + .optional(group, Command.waitUntil(m_endCondition).named("Until Condition")) + .named(name); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java index 17ec140586a..c9c57b97c52 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java @@ -72,8 +72,8 @@ public void setDefaultCommand(Command defaultCommand) { } /** - * Gets the default command that was set by the latest call to - * {@link #setDefaultCommand(Command)}. + * Gets the default command that was set by the latest call to {@link + * #setDefaultCommand(Command)}. * * @return The currently configured default command */ @@ -100,12 +100,13 @@ public CommandBuilder run(Consumer commandBody) { * @return The command builder, for further configuration. */ public CommandBuilder runRepeatedly(Runnable loopBody) { - return run(coroutine -> { - while (true) { - loopBody.run(); - coroutine.yield(); - } - }); + return run( + coroutine -> { + while (true) { + loopBody.run(); + coroutine.yield(); + } + }); } /** @@ -113,7 +114,8 @@ public CommandBuilder runRepeatedly(Runnable loopBody) { * has {@link Command#LOWEST_PRIORITY the lowest priority} and can be interrupted by any other * command. * - *

The default command for every claimable resource is an idle command.

+ *

The default command for every claimable resource is an idle command. + * * @return A new idle command. */ public Command idle() { @@ -122,6 +124,7 @@ public Command idle() { /** * Returns a command that idles this resource for the given duration of time. + * * @param duration How long the resource should idle for. * @return A new idle command. */ diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 177638bbefc..f4293e1dca8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -61,7 +61,6 @@ public class Scheduler implements ProtobufSerializable { /** The default scheduler instance. */ private static final Scheduler s_defaultScheduler = new Scheduler(); - /** * Gets the default scheduler instance for use in a robot program. Some built in command types use * the default scheduler and will not work as expected if used on another scheduler instance. @@ -183,12 +182,9 @@ public enum ScheduleResult { * scheduled another command that shares at least one required resource */ public ScheduleResult schedule(Command command) { - var binding = new Binding( - BindingScope.global(), - BindingType.IMMEDIATE, - command, - new Throwable().getStackTrace() - ); + var binding = + new Binding( + BindingScope.global(), BindingType.IMMEDIATE, command, new Throwable().getStackTrace()); return schedule(binding); } @@ -222,11 +218,7 @@ ScheduleResult schedule(Binding binding) { // so at this point we're guaranteed to be >= priority than anything already on deck evictConflictingOnDeckCommands(command); - var state = new CommandState( - command, - currentCommand(), - buildCoroutine(command), - binding); + var state = new CommandState(command, currentCommand(), buildCoroutine(command), binding); emitEvent(SchedulerEvent.scheduled(command)); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index c08837d301e..a9cac2e55b4 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -8,17 +8,16 @@ import java.util.function.Consumer; /** - * An event that occurs during scheduler processing. This can range from - * {@link Scheduled a command being scheduled} by a trigger or manual call to - * {@link Scheduler#schedule(Command)} to - * {@link Interrupted a command being interrupted by another}. Event listeners can be registered - * with a scheduler via {@link Scheduler#addEventListener(Consumer)}. All events have a timestamp - * to indicate when the event occurred. + * An event that occurs during scheduler processing. This can range from {@link Scheduled a command + * being scheduled} by a trigger or manual call to {@link Scheduler#schedule(Command)} to {@link + * Interrupted a command being interrupted by another}. Event listeners can be registered with a + * scheduler via {@link Scheduler#addEventListener(Consumer)}. All events have a timestamp to + * indicate when the event occurred. */ public sealed interface SchedulerEvent { /** - * The timestamp for when the event occurred. Measured in microseconds since some arbitrary - * start time. + * The timestamp for when the event occurred. Measured in microseconds since some arbitrary start + * time. * * @return The event timestamp. * @see RobotController#getTime() @@ -56,74 +55,65 @@ static SchedulerEvent interrupted(Command command, Command interrupter) { /** * An event marking when a command is scheduled in {@link Scheduler#schedule(Command)}. * - * @param command The command that was scheduled + * @param command The command that was scheduled * @param timestampMicros When the command was scheduled */ - record Scheduled(Command command, long timestampMicros) implements SchedulerEvent { - } + record Scheduled(Command command, long timestampMicros) implements SchedulerEvent {} /** * An event marking when a command starts running. * - * @param command The command that started + * @param command The command that started * @param timestampMicros When the command started */ - record Mounted(Command command, long timestampMicros) implements SchedulerEvent { - } + record Mounted(Command command, long timestampMicros) implements SchedulerEvent {} /** * An event marking when a command yielded control with {@link Coroutine#yield()}. * - * @param command The command that yielded + * @param command The command that yielded * @param timestampMicros When the command yielded */ - record Yielded(Command command, long timestampMicros) implements SchedulerEvent { - } + record Yielded(Command command, long timestampMicros) implements SchedulerEvent {} /** * An event marking when a command completed naturally. * - * @param command The command that completed + * @param command The command that completed * @param timestampMicros When the command completed */ - record Completed(Command command, long timestampMicros) implements SchedulerEvent { - } + record Completed(Command command, long timestampMicros) implements SchedulerEvent {} /** * An event marking when a command threw or encountered an unhanded exception. * - * @param command The command that encountered the error - * @param error The unhandled error + * @param command The command that encountered the error + * @param error The unhandled error * @param timestampMicros When the error occurred */ - record CompletedWithError(Command command, - Throwable error, - long timestampMicros) implements SchedulerEvent { - } + record CompletedWithError(Command command, Throwable error, long timestampMicros) + implements SchedulerEvent {} /** * An event marking when a command was evicted from the scheduler. Commands may be evicted when * they've been scheduled, then another command requiring a shared resource is scheduled - * afterward; when cancelled via {@link Scheduler#cancel(Command)} or - * {@link Scheduler#cancelAll()}; or when they're running and interrupted by another command - * requiring a shared resource. + * afterward; when cancelled via {@link Scheduler#cancel(Command)} or {@link + * Scheduler#cancelAll()}; or when they're running and interrupted by another command requiring a + * shared resource. * - * @param command The command that was evicted + * @param command The command that was evicted * @param timestampMicros When the command was evicted */ - record Evicted(Command command, long timestampMicros) implements SchedulerEvent { - } + record Evicted(Command command, long timestampMicros) implements SchedulerEvent {} /** - * An event marking when a command was interrupted by another. Typically followed by an - * {@link Evicted} event. + * An event marking when a command was interrupted by another. Typically followed by an {@link + * Evicted} event. * - * @param command The command that was interrupted - * @param interrupter The interrupting command + * @param command The command that was interrupted + * @param interrupter The interrupting command * @param timestampMicros When the command was interrupted */ - record Interrupted(Command command, - Command interrupter, - long timestampMicros) implements SchedulerEvent { - } + record Interrupted(Command command, Command interrupter, long timestampMicros) + implements SchedulerEvent {} } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 19e6a1d04df..cede996013a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -28,7 +28,7 @@ public class Sequence implements Command { /** * Creates a new command sequence. * - * @param name the name of the sequence + * @param name the name of the sequence * @param commands the commands to execute within the sequence */ public Sequence(String name, List commands) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index d7c592032db..64949648484 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -12,9 +12,9 @@ import java.util.stream.Collectors; /** - * A builder class to configure and then create a {@link Sequence}. Like {@link CommandBuilder}, - * the final command is created by calling the terminal {@link #named(String)} method, or with - * an automatically generated name using {@link #withAutomaticName()}. + * A builder class to configure and then create a {@link Sequence}. Like {@link CommandBuilder}, the + * final command is created by calling the terminal {@link #named(String)} method, or with an + * automatically generated name using {@link #withAutomaticName()}. */ public class SequenceBuilder { private final List m_steps = new ArrayList<>(); @@ -35,9 +35,9 @@ public SequenceBuilder andThen(Command next) { /** * Adds an end condition to the command group. If this condition is met before all required - * commands have completed, the group will exit early. If multiple end conditions are added - * (e.g. {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end - * condition added will be used and any previously configured condition will be overridden. + * commands have completed, the group will exit early. If multiple end conditions are added (e.g. + * {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end condition + * added will be used and any previously configured condition will be overridden. * * @param endCondition The end condition for the group * @return The builder object, for chaining @@ -62,8 +62,8 @@ public Command named(String name) { // We have a custom end condition, so we need to wrap the group in a race return ParallelGroup.builder() - .optional(seq, Command.waitUntil(m_endCondition).named("Until Condition")) - .named(name); + .optional(seq, Command.waitUntil(m_endCondition).named("Until Condition")) + .named(name); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index b16c3ef3904..d0a5cd02b27 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -38,19 +38,15 @@ public class Trigger implements BooleanSupplier { * first run, when the previous signal value is undefined and unknown. */ private enum Signal { - /** - * The signal is high. - */ + /** The signal is high. */ HIGH, - /** - * The signal is low. - */ + /** The signal is low. */ LOW } /** - * Creates a new trigger based on the given condition. Polled by the scheduler's - * {@link Scheduler#getDefaultEventLoop() default event loop}. + * Creates a new trigger based on the given condition. Polled by the scheduler's {@link + * Scheduler#getDefaultEventLoop() default event loop}. * * @param scheduler The scheduler that should execute triggered commands. * @param condition the condition represented by this trigger @@ -274,13 +270,12 @@ private Signal signal() { } } - /** - * Removes bindings in inactive scopes. - */ + /** Removes bindings in inactive scopes. */ private void clearStaleBindings() { - m_bindings.forEach((_bindingType, bindings) -> { - bindings.removeIf(binding -> !binding.scope().active()); - }); + m_bindings.forEach( + (_bindingType, bindings) -> { + bindings.removeIf(binding -> !binding.scope().active()); + }); } /** @@ -289,8 +284,7 @@ private void clearStaleBindings() { * @param bindingType the binding type to schedule */ private void scheduleBindings(BindingType bindingType) { - m_bindings.getOrDefault(bindingType, List.of()) - .forEach(m_scheduler::schedule); + m_bindings.getOrDefault(bindingType, List.of()).forEach(m_scheduler::schedule); } /** @@ -299,7 +293,8 @@ private void scheduleBindings(BindingType bindingType) { * @param bindingType the binding type to cancel */ private void cancelBindings(BindingType bindingType) { - m_bindings.getOrDefault(bindingType, List.of()) + m_bindings + .getOrDefault(bindingType, List.of()) .forEach(binding -> m_scheduler.cancel(binding.command())); } @@ -324,18 +319,23 @@ private void toggleBindings(BindingType bindingType) { } private void addBinding(BindingType bindingType, Command command) { - BindingScope scope = switch (m_scheduler.currentCommand()) { - // A command is creating a binding - make it scoped to that specific command - case Command c -> BindingScope.forCommand(m_scheduler, c); - - // Creating a binding outside a command - it's global in scope - case null -> BindingScope.global(); - }; + BindingScope scope = + switch (m_scheduler.currentCommand()) { + case Command c -> { + // A command is creating a binding - make it scoped to that specific command + yield BindingScope.forCommand(m_scheduler, c); + } + case null -> { + // Creating a binding outside a command - it's global in scope + yield BindingScope.global(); + } + }; Throwable t = new Throwable("Dummy error to get the binding trace"); StackTraceElement[] frames = t.getStackTrace(); - m_bindings.computeIfAbsent(bindingType, _k -> new ArrayList<>()) + m_bindings + .computeIfAbsent(bindingType, _k -> new ArrayList<>()) .add(new Binding(scope, bindingType, command, frames)); // Ensure this trigger is bound to the event loop. NOP if already bound diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 5e3e6b093ac..64860ea14a3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -5,6 +5,7 @@ package org.wpilib.commands3.button; import edu.wpi.first.math.Pair; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.event.EventLoop; import java.util.HashMap; @@ -85,8 +86,7 @@ public Trigger button(int button, EventLoop loop) { /** * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, - * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button - * loop}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * *

The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, * upper-left is 315). @@ -94,7 +94,7 @@ public Trigger button(int button, EventLoop loop) { * @param angle POV angle in degrees, or -1 for the center / not pressed. * @return a Trigger instance based around this angle of a POV on the HID. */ - public Trigger pov(int angle) { + public Trigger pov(DriverStation.POVDirection angle) { return pov(0, angle, m_scheduler.getDefaultEventLoop()); } @@ -110,34 +110,34 @@ public Trigger pov(int angle) { * Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * @return a Trigger instance based around this angle of a POV on the HID. */ - public Trigger pov(int pov, int angle, EventLoop loop) { + public Trigger pov(int pov, DriverStation.POVDirection angle, EventLoop loop) { var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>()); - // angle can be -1, so use 3600 instead of 360 + // angle.value is a 4 bit bitfield return cache.computeIfAbsent( - pov * 3600 + angle, + pov * 16 + angle.value, k -> new Trigger(m_scheduler, loop, () -> m_hid.getPOV(pov) == angle)); } /** * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV - * on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command - * scheduler button loop}. + * on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler + * button loop}. * * @return a Trigger instance based around the 0 degree angle of a POV on the HID. */ public Trigger povUp() { - return pov(0); + return pov(DriverStation.POVDirection.Up); } /** * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default - * command scheduler button loop}. + * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 45 degree angle of a POV on the HID. */ public Trigger povUpRight() { - return pov(45); + return pov(DriverStation.POVDirection.UpRight); } /** @@ -148,18 +148,18 @@ public Trigger povUpRight() { * @return a Trigger instance based around the 90 degree angle of a POV on the HID. */ public Trigger povRight() { - return pov(90); + return pov(DriverStation.POVDirection.Right); } /** * Constructs a Trigger instance based around the 135 degree angle (right down) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the - * default command scheduler button loop}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default + * command scheduler button loop}. * * @return a Trigger instance based around the 135 degree angle of a POV on the HID. */ public Trigger povDownRight() { - return pov(135); + return pov(DriverStation.POVDirection.DownRight); } /** @@ -170,18 +170,18 @@ public Trigger povDownRight() { * @return a Trigger instance based around the 180 degree angle of a POV on the HID. */ public Trigger povDown() { - return pov(180); + return pov(DriverStation.POVDirection.Down); } /** * Constructs a Trigger instance based around the 225 degree angle (down left) of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the - * default command scheduler button loop}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default + * command scheduler button loop}. * * @return a Trigger instance based around the 225 degree angle of a POV on the HID. */ public Trigger povDownLeft() { - return pov(225); + return pov(DriverStation.POVDirection.DownLeft); } /** @@ -192,35 +192,34 @@ public Trigger povDownLeft() { * @return a Trigger instance based around the 270 degree angle of a POV on the HID. */ public Trigger povLeft() { - return pov(270); + return pov(DriverStation.POVDirection.Left); } /** * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index - * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default - * command scheduler button loop}. + * 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default command + * scheduler button loop}. * * @return a Trigger instance based around the 315 degree angle of a POV on the HID. */ public Trigger povUpLeft() { - return pov(315); + return pov(DriverStation.POVDirection.UpLeft); } /** * Constructs a Trigger instance based around the center (not pressed) position of the default - * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the - * default command scheduler button loop}. + * (index 0) POV on the HID, attached to {@link Scheduler#getDefaultEventLoop() the default + * command scheduler button loop}. * * @return a Trigger instance based around the center position of a POV on the HID. */ public Trigger povCenter() { - return pov(-1); + return pov(DriverStation.POVDirection.Center); } /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button - * loop}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * * @param axis The axis to read, starting at 0 * @param threshold The value below which this trigger should return true. @@ -250,8 +249,7 @@ public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { /** * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, - * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button - * loop}. + * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * * @param axis The axis to read, starting at 0 * @param threshold The value above which this trigger should return true. @@ -298,16 +296,15 @@ public Trigger axisMagnitudeGreaterThan(int axis, double threshold, EventLoop lo /** * Constructs a Trigger instance that is true when the axis magnitude value is greater than {@code - * threshold}, attached to {@link Scheduler#getDefaultEventLoop() the default command - * scheduler button loop}. + * threshold}, attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler + * button loop}. * * @param axis The axis to read, starting at 0 * @param threshold The value above which this trigger should return true. * @return a Trigger instance that is true when the deadbanded axis value is active (non-zero). */ public Trigger axisMagnitudeGreaterThan(int axis, double threshold) { - return axisMagnitudeGreaterThan( - axis, threshold, m_scheduler.getDefaultEventLoop()); + return axisMagnitudeGreaterThan(axis, threshold, m_scheduler.getDefaultEventLoop()); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java index 92f26a5b1c3..fdb91731ec8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java @@ -6,6 +6,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.GenericHID; import org.wpilib.commands3.Trigger; @@ -18,7 +19,7 @@ public class POVButton extends Trigger { * @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) { + public POVButton(GenericHID joystick, DriverStation.POVDirection angle, int povNumber) { super(() -> joystick.getPOV(povNumber) == angle); requireNonNullParam(joystick, "joystick", "POVButton"); } @@ -29,7 +30,7 @@ public POVButton(GenericHID joystick, int angle, int povNumber) { * @param joystick The GenericHID object that has the POV * @param angle The desired angle (e.g. 90, 270) */ - public POVButton(GenericHID joystick, int angle) { + public POVButton(GenericHID joystick, DriverStation.POVDirection angle) { this(joystick, angle, 0); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index 48246958a69..a70b7feaf81 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -41,7 +41,8 @@ public Command unpack(ProtobufCommand msg) { @Override public void pack(ProtobufCommand msg, Command command) { msg.setId(m_scheduler.runId(command)); - if (m_scheduler.getParentOf(command) instanceof Command parent) { + Command parent = m_scheduler.getParentOf(command); + if (parent != null) { msg.setParentId(m_scheduler.runId(parent)); } msg.setName(command.name()); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index 906a338e513..b57a8e39943 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -20,12 +20,10 @@ class CoroutineTest { Scheduler m_scheduler; - ContinuationScope m_scope; @BeforeEach void setup() { m_scheduler = new Scheduler(); - m_scope = new ContinuationScope("Test Scope"); RobotController.setTimeSource(() -> System.nanoTime() / 1000L); } @@ -35,10 +33,13 @@ void forkMany() { var b = new NullCommand(); var c = new NullCommand(); - var all = Command.noRequirements(co -> { - co.fork(a, b, c); - co.park(); - }).named("Fork Many"); + var all = + Command.noRequirements( + co -> { + co.fork(a, b, c); + co.park(); + }) + .named("Fork Many"); m_scheduler.schedule(all); m_scheduler.run(); @@ -52,14 +53,17 @@ void yieldInSynchronizedBlock() { Object mutex = new Object(); AtomicInteger i = new AtomicInteger(0); - var yieldInSynchronized = Command.noRequirements(co -> { - while (true) { - synchronized (mutex) { - i.incrementAndGet(); - co.yield(); - } - } - }).named("Yield In Synchronized Block"); + var yieldInSynchronized = + Command.noRequirements( + co -> { + while (true) { + synchronized (mutex) { + i.incrementAndGet(); + co.yield(); + } + } + }) + .named("Yield In Synchronized Block"); m_scheduler.schedule(yieldInSynchronized); @@ -80,17 +84,20 @@ void yieldInLockBody() { Lock lock = new ReentrantLock(); AtomicInteger i = new AtomicInteger(0); - var yieldInLock = Command.noRequirements(co -> { - while (true) { - lock.lock(); - try { - i.incrementAndGet(); - co.yield(); - } finally { - lock.unlock(); - } - } - }).named("Increment In Lock Block"); + var yieldInLock = + Command.noRequirements( + co -> { + while (true) { + lock.lock(); + try { + i.incrementAndGet(); + co.yield(); + } finally { + lock.unlock(); + } + } + }) + .named("Increment In Lock Block"); m_scheduler.schedule(yieldInLock); m_scheduler.run(); @@ -101,9 +108,12 @@ void yieldInLockBody() { void coroutineEscapingCommand() { AtomicReference escapeeCallback = new AtomicReference<>(); - var badCommand = Command.noRequirements(co -> { - escapeeCallback.set(co::yield); - }).named("Bad Command"); + var badCommand = + Command.noRequirements( + co -> { + escapeeCallback.set(co::yield); + }) + .named("Bad Command"); m_scheduler.schedule(badCommand); m_scheduler.run(); @@ -123,17 +133,23 @@ void awaitAnyCleansUp() { AtomicBoolean ranAfterAwait = new AtomicBoolean(false); var firstInner = Command.noRequirements(c2 -> firstRan.set(true)).named("First"); - var secondInner = Command.noRequirements(c2 -> { - secondRan.set(true); - c2.park(); - }).named("Second"); - - var outer = Command.noRequirements(co -> { - co.awaitAny(firstInner, secondInner); - - ranAfterAwait.set(true); - co.park(); // prevent exiting - }).named("Command"); + var secondInner = + Command.noRequirements( + c2 -> { + secondRan.set(true); + c2.park(); + }) + .named("Second"); + + var outer = + Command.noRequirements( + co -> { + co.awaitAny(firstInner, secondInner); + + ranAfterAwait.set(true); + co.park(); // prevent exiting + }) + .named("Command"); m_scheduler.schedule(outer); m_scheduler.run(); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index eff742feccf..79c87ce5f4a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -165,8 +165,7 @@ void errorDetection() { }) .named("Bad Behavior"); - new Trigger(m_scheduler, () -> true) - .onTrue(command); + new Trigger(m_scheduler, () -> true).onTrue(command); try { m_scheduler.run(); @@ -188,17 +187,25 @@ void errorDetection() { @Test void nestedErrorDetection() { - var command = Command.noRequirements(co -> { - co.await(Command.noRequirements(c2 -> { - new Trigger(m_scheduler, () -> true) - .onTrue(Command.noRequirements(c3 -> { - // Throws IndexOutOfBoundsException - new ArrayList<>(0).get(-1); - }).named("Throws IndexOutOfBounds") - ); - c2.park(); - }).named("Schedules With Trigger")); - }).named("Schedules Directly"); + var command = + Command.noRequirements( + co -> { + co.await( + Command.noRequirements( + c2 -> { + new Trigger(m_scheduler, () -> true) + .onTrue( + Command.noRequirements( + c3 -> { + // Throws IndexOutOfBoundsException + new ArrayList<>(0).get(-1); + }) + .named("Throws IndexOutOfBounds")); + c2.park(); + }) + .named("Schedules With Trigger")); + }) + .named("Schedules Directly"); m_scheduler.schedule(command); @@ -270,10 +277,7 @@ void cancelOnInterruptDoesNotResume() { var resource = new RequireableResource("Resource", m_scheduler); var interrupter = - Command.requiring(resource) - .executing(coroutine -> {}) - .withPriority(2) - .named("Interrupter"); + Command.requiring(resource).executing(coroutine -> {}).withPriority(2).named("Interrupter"); var canceledCommand = Command.requiring(resource) @@ -443,19 +447,21 @@ void compositionsDoNotSelfCancel() { @Test void compositionsDoNotCancelParent() { var res = new RequireableResource("The Resource", m_scheduler); - var group = res.run(co -> { - co.fork(res.run(Coroutine::park).named("First Child")); - co.fork(res.run(Coroutine::park).named("Second Child")); - co.park(); - }).named("Group"); + var group = + res.run( + co -> { + co.fork(res.run(Coroutine::park).named("First Child")); + co.fork(res.run(Coroutine::park).named("Second Child")); + co.park(); + }) + .named("Group"); m_scheduler.schedule(group); m_scheduler.run(); assertEquals( List.of("Group", "Second Child"), - m_scheduler.getRunningCommands().stream().map(Command::name).toList() - ); + m_scheduler.getRunningCommands().stream().map(Command::name).toList()); } @Test @@ -499,10 +505,10 @@ void compositionsCannotAwaitConflictingCommands() { m_scheduler.run(); fail("An exception should have been thrown"); } catch (IllegalArgumentException iae) { - assertEquals( - "Command Second requires resources that are already used by First. " - + "Both require The Resource", - iae.getMessage()); + assertEquals( + "Command Second requires resources that are already used by First. " + + "Both require The Resource", + iae.getMessage()); } catch (Exception e) { fail("Unexpected exception: " + e); } @@ -602,8 +608,7 @@ void sideloadThrowingException() { // An exception raised in a sideload function should bubble up assertEquals( - "Bang!", - assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); + "Bang!", assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); } @Test @@ -729,12 +734,10 @@ void protobuf() { m_scheduler.totalRuntimeMs(c2Command), m_scheduler.runId(c2Command), // id m_scheduler.runId(group), // parent - m_scheduler.lastCommandRuntimeMs(c3Command), m_scheduler.totalRuntimeMs(c3Command), m_scheduler.runId(c3Command), // id m_scheduler.runId(c2Command), // parent - m_scheduler.lastCommandRuntimeMs(parkCommand), m_scheduler.totalRuntimeMs(parkCommand), m_scheduler.runId(parkCommand), // id @@ -749,21 +752,32 @@ void siblingsInCompositionCanShareRequirements() { var firstRan = new AtomicBoolean(false); var secondRan = new AtomicBoolean(false); - var first = resource.run(c -> { - firstRan.set(true); - c.park(); - }).named("First"); + var first = + resource + .run( + c -> { + firstRan.set(true); + c.park(); + }) + .named("First"); - var second = resource.run(c -> { - secondRan.set(true); - c.park(); - }).named("Second"); + var second = + resource + .run( + c -> { + secondRan.set(true); + c.park(); + }) + .named("Second"); - var group = Command.noRequirements(co -> { - co.fork(first); - co.fork(second); - co.park(); - }).named("Group"); + var group = + Command.noRequirements( + co -> { + co.fork(first); + co.fork(second); + co.park(); + }) + .named("Group"); m_scheduler.schedule(group); m_scheduler.run(); @@ -771,8 +785,7 @@ void siblingsInCompositionCanShareRequirements() { assertTrue(firstRan.get(), "First child should have run to a yield point"); assertTrue(secondRan.get(), "Second child should have run to a yield point"); assertFalse( - m_scheduler.isScheduledOrRunning(first), - "First child should have been interrupted"); + m_scheduler.isScheduledOrRunning(first), "First child should have been interrupted"); assertTrue(m_scheduler.isRunning(second), "Second child should still be running"); assertTrue(m_scheduler.isRunning(group), "Group should still be running"); } @@ -782,19 +795,28 @@ void nestedOneShotCompositionsAllRunInOneCycle() { var runs = new AtomicInteger(0); Supplier makeOneShot = () -> Command.noRequirements(_c -> runs.incrementAndGet()).named("One Shot"); - var command = Command.noRequirements(co -> { - co.fork(makeOneShot.get()); - co.fork(makeOneShot.get()); - co.fork(Command.noRequirements(inner -> inner.fork(makeOneShot.get())).named("Inner")); - co.fork( - Command.noRequirements(co2 -> { - co2.fork(makeOneShot.get()); - co2.fork( - Command.noRequirements(co3 -> { - co3.fork(makeOneShot.get()); - }).named("3")); - }).named("2")); - }).named("Command"); + var command = + Command.noRequirements( + co -> { + co.fork(makeOneShot.get()); + co.fork(makeOneShot.get()); + co.fork( + Command.noRequirements(inner -> inner.fork(makeOneShot.get())) + .named("Inner")); + co.fork( + Command.noRequirements( + co2 -> { + co2.fork(makeOneShot.get()); + co2.fork( + Command.noRequirements( + co3 -> { + co3.fork(makeOneShot.get()); + }) + .named("3")); + }) + .named("2")); + }) + .named("Command"); m_scheduler.schedule(command); m_scheduler.run(); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index b45a454c862..937b98cad60 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -45,14 +45,12 @@ void onFalse() { m_scheduler.run(); assertTrue( - m_scheduler.isRunning(command), - "Command should be scheduled when signal starts low"); + m_scheduler.isRunning(command), "Command should be scheduled when signal starts low"); signal.set(true); m_scheduler.run(); assertTrue( - m_scheduler.isRunning(command), - "Command should still be running rising falling edge"); + m_scheduler.isRunning(command), "Command should still be running rising falling edge"); } @Test @@ -65,15 +63,11 @@ void whileTrue() { signal.set(true); m_scheduler.run(); - assertTrue( - m_scheduler.isRunning(command), - "Command was not scheduled on rising edge"); + assertTrue(m_scheduler.isRunning(command), "Command was not scheduled on rising edge"); signal.set(false); m_scheduler.run(); - assertFalse( - m_scheduler.isRunning(command), - "Command should be cancelled on falling edge"); + assertFalse(m_scheduler.isRunning(command), "Command should be cancelled on falling edge"); } @Test @@ -85,14 +79,11 @@ void whileFalse() { m_scheduler.run(); assertTrue( - m_scheduler.isRunning(command), - "Command should be scheduled when signal starts low"); + m_scheduler.isRunning(command), "Command should be scheduled when signal starts low"); signal.set(true); m_scheduler.run(); - assertFalse( - m_scheduler.isRunning(command), - "Command should be cancelled on rising edge"); + assertFalse(m_scheduler.isRunning(command), "Command should be cancelled on rising edge"); } @Test @@ -142,17 +133,23 @@ void commandScoping() { var innerRan = new AtomicBoolean(false); var innerSignal = new AtomicBoolean(false); - var inner = Command.noRequirements(co -> { - while (true) { - innerRan.set(true); - co.park(); - } - }).named("Inner"); - - var outer = Command.noRequirements(co -> { - new Trigger(m_scheduler, innerSignal::get).onTrue(inner); - co.yield(); - }).named("Outer"); + var inner = + Command.noRequirements( + co -> { + while (true) { + innerRan.set(true); + co.park(); + } + }) + .named("Inner"); + + var outer = + Command.noRequirements( + co -> { + new Trigger(m_scheduler, innerSignal::get).onTrue(inner); + co.yield(); + }) + .named("Outer"); m_scheduler.schedule(outer); m_scheduler.run(); diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index 35ff5c83025..b989c634811 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -152,6 +152,21 @@ + + + + + + + + + + + + + + + From 40a5cb089f1b224c0007a45a1886b4e23bc0c437 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 19:20:28 -0400 Subject: [PATCH 051/153] Remove old examples --- .../examples/coroutines/AsyncCommandBot.java | 102 ----------------- .../examples/coroutines/Constants.java | 90 --------------- .../wpilibj/examples/coroutines/Main.java | 25 ----- .../wpilibj/examples/coroutines/Robot.java | 86 --------------- .../examples/coroutines/subsystems/Drive.java | 103 ------------------ .../coroutines/subsystems/Intake.java | 46 -------- .../coroutines/subsystems/Pneumatics.java | 71 ------------ .../coroutines/subsystems/Shooter.java | 66 ----------- .../coroutines/subsystems/Storage.java | 47 -------- 9 files changed, 636 deletions(-) delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java delete mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java deleted file mode 100644 index fdb00185038..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/AsyncCommandBot.java +++ /dev/null @@ -1,102 +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.examples.coroutines; - -import org.wpilib.commands3.Command; -import org.wpilib.commands3.button.CommandXboxController; -import org.wpilib.commands3.button.Trigger; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.AutoConstants; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.OIConstants; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; -import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Drive; -import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Intake; -import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Pneumatics; -import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Shooter; -import edu.wpi.first.wpilibj.examples.coroutines.subsystems.Storage; - -/** - * This class is where the bulk of the robot should be declared. Since Command-based is a - * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} - * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including - * subsystems, commands, and button mappings) should be declared here. - */ -public class AsyncCommandBot { - // The robot's subsystems - private final Drive m_drive = new Drive(); - private final Intake m_intake = new Intake(); - private final Storage m_storage = new Storage(); - private final Shooter m_shooter = new Shooter(); - private final Pneumatics m_pneumatics = new Pneumatics(); - - // The driver's controller - private final CommandXboxController m_driverController = - new CommandXboxController(OIConstants.kDriverControllerPort); - - /** - * Use this method to define bindings between conditions and commands. These are useful for - * automating robot behaviors based on button and sensor input. - * - *

Should be called during {@link Robot#robotInit()}. - * - *

Event binding methods are available on the {@link Trigger} class. - */ - public void configureBindings() { - // Automatically run the storage motor whenever the ball storage is not full, - // and turn it off whenever it fills. Uses subsystem-hosted trigger to - // improve readability and make inter-subsystem communication easier. - m_storage.hasCargo.whileFalse(m_storage.runCommand()); - - // Automatically disable and retract the intake whenever the ball storage is full. - m_storage.hasCargo.onTrue(m_intake.retractCommand()); - - // Control the drive with split-stick arcade controls - m_drive.setDefaultCommand( - m_drive.arcadeDriveCommand( - () -> -m_driverController.getLeftY(), () -> -m_driverController.getRightX())); - - // Deploy the intake with the X button - m_driverController.x().onTrue(m_intake.intakeCommand()); - // Retract the intake with the Y button - m_driverController.y().onTrue(m_intake.retractCommand()); - - // Fire the shooter with the A button - m_driverController.a().onTrue(loadAndShoot()); - - // Toggle compressor with the Start button - m_driverController.start() - .onTrue(m_pneumatics.disableCompressor()) - .onFalse(m_pneumatics.enableCompressor()); - } - - private Command loadAndShoot() { - return Command - .requiring(m_shooter, m_storage) - .executing((coroutine) -> { - while (coroutine.yield()) { - m_storage.run(); - m_shooter.ramp(ShooterConstants.kShooterTarget); - - if (m_shooter.atSetpoint()) { - m_shooter.feed(); - } else { - m_shooter.stop(); - } - } - }) - .named("Shoot"); - } - - /** - * Use this to define the command that runs during autonomous. - * - *

Scheduled during {@link Robot#autonomousInit()}. - */ - public Command getAutonomousCommand() { - // Drive forward for 2 meters at half speed with a 3 second timeout - return m_drive - .driveDistanceCommand(AutoConstants.kDriveDistance, AutoConstants.kDriveSpeed) - .withTimeout(AutoConstants.kTimeout); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java deleted file mode 100644 index 21b9d680a8b..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Constants.java +++ /dev/null @@ -1,90 +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.examples.coroutines; - -import static edu.wpi.first.units.Units.Meters; -import static edu.wpi.first.units.Units.RotationsPerSecond; -import static edu.wpi.first.units.Units.Seconds; - -import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.measure.AngularVelocity; -import edu.wpi.first.units.measure.Distance; -import edu.wpi.first.units.measure.Time; - -/** - * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean - * constants. This class should not be used for any other purpose. All constants should be declared - * globally (i.e. public static). Do not put anything functional in this class. - * - *

It is advised to statically import this class (or one of its inner classes) wherever the - * constants are needed, to reduce verbosity. - */ -public final class Constants { - public static final class DriveConstants { - public static final int kLeftMotor1Port = 0; - public static final int kLeftMotor2Port = 1; - public static final int kRightMotor1Port = 2; - public static final int kRightMotor2Port = 3; - - public static final int[] kLeftEncoderPorts = {0, 1}; - public static final int[] kRightEncoderPorts = {2, 3}; - public static final boolean kLeftEncoderReversed = false; - public static final boolean kRightEncoderReversed = true; - - public static final int kEncoderCPR = 1024; - public static final double kWheelDiameterMeters = Units.inchesToMeters(6); - public static final double kEncoderDistancePerPulse = - // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR; - } - - public static final class ShooterConstants { - public static final int[] kEncoderPorts = {4, 5}; - public static final boolean kEncoderReversed = false; - public static final int kEncoderCPR = 1024; - public static final double kEncoderDistancePerPulse = - // Distance units will be rotations - 1.0 / (double) kEncoderCPR; - - public static final int kShooterMotorPort = 4; - public static final int kFeederMotorPort = 5; - - public static final double kShooterFreeRPS = 5300; - public static final AngularVelocity kShooterTarget = RotationsPerSecond.of(4000); - public static final double kShooterToleranceRPS = 50; - - // These are not real PID gains, and will have to be tuned for your specific robot. - public static final double kP = 1; - - // On a real robot the feedforward constants should be empirically determined; these are - // reasonable guesses. - public static final double kSVolts = 0.05; - public static final double kVVoltSecondsPerRotation = - // Should have value 12V at free speed... - 12.0 / kShooterFreeRPS; - - public static final double kFeederSpeed = 0.5; - } - - public static final class IntakeConstants { - public static final int kMotorPort = 6; - public static final int[] kSolenoidPorts = {2, 3}; - } - - public static final class StorageConstants { - public static final int kMotorPort = 7; - public static final int kBallSensorPort = 6; - } - - public static final class AutoConstants { - public static final Time kTimeout = Seconds.of(3); - public static final Distance kDriveDistance = Meters.of(2); - public static final double kDriveSpeed = 0.5; - } - - public static final class OIConstants { - public static final int kDriverControllerPort = 0; - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java deleted file mode 100644 index f0fe058ddd4..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Main.java +++ /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. - -package edu.wpi.first.wpilibj.examples.coroutines; - -import edu.wpi.first.wpilibj.RobotBase; - -/** - * Do NOT add any static variables to this class, or any initialization at all. Unless you know what - * you are doing, do not modify this file except to change the parameter class to the startRobot - * call. - */ -public final class Main { - private Main() {} - - /** - * Main initialization function. Do not perform any initialization here. - * - *

If you change your main robot class, change the parameter type. - */ - public static void main(String... args) { - RobotBase.startRobot(Robot::new); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.java deleted file mode 100644 index 54e901d6696..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/Robot.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.examples.coroutines; - -import edu.wpi.first.wpilibj.TimedRobot; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.Scheduler; - -/** - * The VM is configured to automatically run this class, and to call the functions corresponding to - * each mode, as described in the TimedRobot documentation. If you change the name of this class or - * the package after creating this project, you must also update the build.gradle file in the - * project. - */ -public class Robot extends TimedRobot { - private Command m_autonomousCommand; - - private final AsyncCommandBot m_robot = new AsyncCommandBot(); - - /** - * This function is run when the robot is first started up and should be used for any - * initialization code. - */ - @Override - public void robotInit() { - // Configure default commands and condition bindings on robot startup - m_robot.configureBindings(); - } - - /** - * This function is called every robot packet, no matter the mode. Use this for items like - * diagnostics that you want ran during disabled, autonomous, teleoperated and test. - * - *

This runs after the mode specific periodic functions, but before LiveWindow and - * SmartDashboard integrated updating. - */ - @Override - public void robotPeriodic() { - Scheduler.getInstance().run(); - } - - /** This function is called once each time the robot enters Disabled mode. */ - @Override - public void disabledInit() {} - - @Override - public void disabledPeriodic() {} - - @Override - public void autonomousInit() { - m_autonomousCommand = m_robot.getAutonomousCommand(); - - if (m_autonomousCommand != null) { - Scheduler.getInstance().schedule(m_autonomousCommand); - } - } - - /** This function is called periodically during autonomous. */ - @Override - public void autonomousPeriodic() {} - - @Override - public void teleopInit() { - // This makes sure that the autonomous stops running when - // teleop starts running. If you want the autonomous to - // continue until interrupted by another command, remove - // this line or comment it out. - Scheduler.getInstance().cancel(m_autonomousCommand); - } - - /** This function is called periodically during operator control. */ - @Override - public void teleopPeriodic() {} - - @Override - public void testInit() { - // Cancels all running commands at the start of test mode. - Scheduler.getInstance().cancelAll(); - } - - /** This function is called periodically during test mode. */ - @Override - public void testPeriodic() {} -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.java deleted file mode 100644 index d0264d8c41c..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Drive.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.examples.coroutines.subsystems; - -import static edu.wpi.first.units.Units.Meters; - -import edu.wpi.first.units.measure.Distance; -import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.Encoder; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.RequireableResource; -import edu.wpi.first.wpilibj.drive.DifferentialDrive; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; -import java.util.function.DoubleSupplier; - -public class Drive extends RequireableResource { - // The motors on the left side of the drive. - private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); - private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); - - // The motors on the right side of the drive. - private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); - private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); - - // The robot's drive - private final DifferentialDrive m_drive = - new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); - - // The left-side drive encoder - private final Encoder m_leftEncoder = - new Encoder( - DriveConstants.kLeftEncoderPorts[0], - DriveConstants.kLeftEncoderPorts[1], - DriveConstants.kLeftEncoderReversed); - - // The right-side drive encoder - private final Encoder m_rightEncoder = - new Encoder( - DriveConstants.kRightEncoderPorts[0], - DriveConstants.kRightEncoderPorts[1], - DriveConstants.kRightEncoderReversed); - - /** Creates a new Drive subsystem. */ - public Drive() { - super("Drive"); - - SendableRegistry.addChild(m_drive, m_leftLeader); - SendableRegistry.addChild(m_drive, m_rightLeader); - - m_leftLeader.addFollower(m_leftFollower); - m_rightLeader.addFollower(m_rightFollower); - - // We need to invert one side of the drivetrain so that positive voltages - // result in both sides moving forward. Depending on how your robot's - // gearbox is constructed, you might have to invert the left side instead. - m_rightLeader.setInverted(true); - - // Sets the distance per pulse for the encoders - m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); - m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); - } - - /** - * Returns a command that drives the robot with arcade controls. - * - * @param fwd the commanded forward movement - * @param rot the commanded rotation - */ - public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) { - // A split-stick arcade command, with forward/backward controlled by the left - // hand, and turning controlled by the right. - return run((coroutine) -> { - while (coroutine.yield()) { - m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble()); - } - }).named("arcadeDrive"); - } - - /** - * Returns a command that drives the robot forward a specified distance at a specified speed. - * - * @param distance The distance to drive forward in meters - * @param speed The fraction of max speed at which to drive - */ - public Command driveDistanceCommand(Distance distance, double speed) { - double distanceMeters = distance.in(Meters); - - return run((coroutine) -> { - m_leftEncoder.reset(); - m_rightEncoder.reset(); - - while (Math.max(m_leftEncoder.getDistance(), m_rightEncoder.getDistance()) < distanceMeters) { - coroutine.yield(); - m_drive.arcadeDrive(speed, 0); - } - - m_drive.stopMotor(); - }).named("DriveDistance[" + distance.toLongString() + ", @" + speed + "]"); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.java deleted file mode 100644 index 57ca1860828..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Intake.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.examples.coroutines.subsystems; - -import static edu.wpi.first.wpilibj.examples.coroutines.Constants.IntakeConstants; - -import edu.wpi.first.wpilibj.DoubleSolenoid; -import edu.wpi.first.wpilibj.PneumaticsModuleType; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.RequireableResource; -import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; - -public class Intake extends RequireableResource { - private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort); - - // Double solenoid connected to two channels of a PCM with the default CAN ID - private final DoubleSolenoid m_pistons = - new DoubleSolenoid( - PneumaticsModuleType.CTREPCM, - IntakeConstants.kSolenoidPorts[0], - IntakeConstants.kSolenoidPorts[1]); - - public Intake() { - super("Intake"); - } - - /** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */ - public Command intakeCommand() { - return run((coroutine) -> { - m_pistons.set(DoubleSolenoid.Value.kForward); - while (coroutine.yield()) { - m_motor.set(1); - } - }).named("Intake"); - } - - /** Returns a command that turns off and retracts the intake. */ - public Command retractCommand() { - return run((coroutine) -> { - m_motor.disable(); - m_pistons.set(DoubleSolenoid.Value.kReverse); - }).named("Retract"); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java deleted file mode 100644 index aeb1b1b2962..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Pneumatics.java +++ /dev/null @@ -1,71 +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.examples.coroutines.subsystems; - -import edu.wpi.first.wpilibj.AnalogPotentiometer; -import edu.wpi.first.wpilibj.Compressor; -import edu.wpi.first.wpilibj.PneumaticsModuleType; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.RequireableResource; -import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; - -/** Subsystem for managing the compressor, pressure sensor, etc. */ -public class Pneumatics extends RequireableResource { - // External analog pressure sensor - // product-specific voltage->pressure conversion, see product manual - // in this case, 250(V/5)-25 - // the scale parameter in the AnalogPotentiometer constructor is scaled from 1 instead of 5, - // so if r is the raw AnalogPotentiometer output, the pressure is 250r-25 - static final double kScale = 250; - static final double kOffset = -25; - private final AnalogPotentiometer m_pressureTransducer = - new AnalogPotentiometer(/* the AnalogIn port*/ 2, kScale, kOffset); - - // Compressor connected to a PCM with a default CAN ID (0) - // Note: the compressor is enabled by default - private final Compressor m_compressor = new Compressor(PneumaticsModuleType.CTREPCM); - - public Pneumatics() { - super("Pneumatics"); - var tab = Shuffleboard.getTab("Pneumatics"); - tab.addDouble("External Pressure [PSI]", this::getPressure); - } - - /** - * Query the analog pressure sensor. - * - * @return the measured pressure, in PSI - */ - private double getPressure() { - // Get the pressure (in PSI) from an analog pressure sensor connected to the RIO. - return m_pressureTransducer.get(); - } - - /** - * Disable the compressor closed-loop control. The compressor can be re-enabled with - * {@link #enableCompressor()}. - * - * @return command - */ - public Command disableCompressor() { - return run((coroutine) -> { - m_compressor.disable(); - coroutine.park(); - }).named("Disable Compressor"); - } - - /** - * Enable the compressor closed-loop control. The compressor can be disabled again with - * {@link #disableCompressor()}. - * - * @return command - */ - public Command enableCompressor() { - return run((coroutine) -> { - m_compressor.enableDigital(); - coroutine.park(); - }).named("Enable Compressor"); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java deleted file mode 100644 index 844bf9dbc08..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Shooter.java +++ /dev/null @@ -1,66 +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.examples.coroutines.subsystems; - -import static edu.wpi.first.units.Units.RotationsPerSecond; -import static edu.wpi.first.units.Units.Volts; - -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; -import edu.wpi.first.units.measure.AngularVelocity; -import edu.wpi.first.wpilibj.Encoder; -import org.wpilib.commands3.RequireableResource; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.ShooterConstants; -import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; - -public class Shooter extends RequireableResource { - private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort); - private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort); - private final Encoder m_shooterEncoder = - new Encoder( - ShooterConstants.kEncoderPorts[0], - ShooterConstants.kEncoderPorts[1], - ShooterConstants.kEncoderReversed); - private final SimpleMotorFeedforward m_shooterFeedforward = - new SimpleMotorFeedforward( - ShooterConstants.kSVolts, ShooterConstants.kVVoltSecondsPerRotation); - private final PIDController m_shooterFeedback = new PIDController(ShooterConstants.kP, 0.0, 0.0); - - /** The shooter subsystem for the robot. */ - public Shooter() { - super("Shooter"); - m_shooterFeedback.setTolerance(ShooterConstants.kShooterToleranceRPS); - m_shooterEncoder.setDistancePerPulse(ShooterConstants.kEncoderDistancePerPulse); - - // Set default command to turn off both the shooter and feeder motors, and then idle - setDefaultCommand( - run( - (coroutine) -> { - m_shooterMotor.disable(); - m_feederMotor.disable(); - coroutine.park(); - }) - .named("Idle")); - } - - public void ramp(AngularVelocity setpoint) { - m_shooterMotor.set( - m_shooterFeedforward.calculate(setpoint).in(Volts) - + m_shooterFeedback.calculate( - m_shooterEncoder.getRate(), setpoint.in(RotationsPerSecond))); - } - - public boolean atSetpoint() { - return m_shooterFeedback.atSetpoint(); - } - - public void feed() { - m_feederMotor.set(1); - } - - public void stop() { - m_feederMotor.set(0); - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java deleted file mode 100644 index 7f26f19402c..00000000000 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/coroutines/subsystems/Storage.java +++ /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. - -package edu.wpi.first.wpilibj.examples.coroutines.subsystems; - -import edu.wpi.first.wpilibj.DigitalInput; -import org.wpilib.commands3.Command; -import org.wpilib.commands3.RequireableResource; -import org.wpilib.commands3.button.Trigger; -import edu.wpi.first.wpilibj.examples.coroutines.Constants.StorageConstants; -import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; - -public class Storage extends RequireableResource { - private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort); - private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort); - - // Expose trigger from subsystem to improve readability and ease - // inter-subsystem communications - /** Whether the ball storage is full. */ - @SuppressWarnings("checkstyle:MemberName") - public final Trigger hasCargo = new Trigger(m_ballSensor::get); - - /** Create a new Storage subsystem. */ - public Storage() { - super("Storage"); - - // Set default command to turn off the storage motor and then idle - setDefaultCommand(run((coroutine) -> { - m_motor.disable(); - coroutine.park(); - }).named("Idle")); - } - - public void run() { - m_motor.set(1); - } - - /** Returns a command that runs the storage motor indefinitely. */ - public Command runCommand() { - return run((coroutine) -> { - while (coroutine.yield()) { - run(); - } - }).named("Run"); - } -} From 081289c1dd08b64b16d418a57abb3d2fa9371212 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 19:20:36 -0400 Subject: [PATCH 052/153] Formatting --- commandsv3/src/main/java/org/wpilib/commands3/Command.java | 2 +- commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 3be3a9dcc0d..4cc94c01e9a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -57,7 +57,7 @@ * ).withName("The Command"); * * // Can be represented with a 2025-style async-based definition - * Command command = requiredSubsystem.run((coroutine) -> { + * Command command = requiredSubsystem.run(coroutine -> { * initialize(); * while (!isFinished()) { * coroutine.yield(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 97227921848..7e7a91625a2 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -78,7 +78,7 @@ public void park() { * parent command cancels it. The parent command will continue executing while the forked command * runs, and can resync with the forked command using {@link #await(Command)}. * - *

{@snippet lang = java: Command example() { return Command.noRequirements((coroutine) -> { + *

{@snippet lang = java: Command example() { return Command.noRequirements(coroutine -> { * Command inner = ...; coroutine.fork(inner); // ... do more things // then sync back up with the * inner command coroutine.await(inner); }).named("Example"); } } * @@ -228,7 +228,7 @@ private static void validateNoConflicts(Collection commands) { * *

For example, a basic autonomous routine that drives straight for 5 seconds: * - *

{@snippet lang = java : Command timedDrive() { return drivebase.run((coroutine) -> { + *

{@snippet lang = java : Command timedDrive() { return drivebase.run(coroutine -> { * drivebase.tankDrive(1, 1); coroutine.wait(Seconds.of(5)); drivebase.stop(); }).named("Timed * Drive"); } } * From c6145d620d9fe7d36166d20dac8b55b75ec890be Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 20:12:43 -0400 Subject: [PATCH 053/153] Formatting --- commandsv3/src/generate/main/java/commandhid.java.jinja | 2 +- .../org/wpilib/commands3/button/CommandPS4Controller.java | 2 +- .../org/wpilib/commands3/button/CommandPS5Controller.java | 2 +- .../wpilib/commands3/button/CommandStadiaController.java | 2 +- .../org/wpilib/commands3/button/CommandXboxController.java | 2 +- design-docs/commands-v3.md | 6 +++--- 6 files changed, 8 insertions(+), 8 deletions(-) diff --git a/commandsv3/src/generate/main/java/commandhid.java.jinja b/commandsv3/src/generate/main/java/commandhid.java.jinja index 7186c790e62..777bbcbb70b 100644 --- a/commandsv3/src/generate/main/java/commandhid.java.jinja +++ b/commandsv3/src/generate/main/java/commandhid.java.jinja @@ -31,7 +31,7 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { super(port); m_hid = new {{ ConsoleName }}Controller(port); } - + /** * Construct an instance of a controller. * diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index 03c18f38eb2..c67f035a1fe 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -29,7 +29,7 @@ public CommandPS4Controller(int port) { super(port); m_hid = new PS4Controller(port); } - + /** * Construct an instance of a controller. * diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 670423824b1..0f9e73eba58 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -29,7 +29,7 @@ public CommandPS5Controller(int port) { super(port); m_hid = new PS5Controller(port); } - + /** * Construct an instance of a controller. * diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java index 254f0bfc522..6317656853d 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -29,7 +29,7 @@ public CommandStadiaController(int port) { super(port); m_hid = new StadiaController(port); } - + /** * Construct an instance of a controller. * diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java index 2bb4b437e47..c4902c81f37 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -29,7 +29,7 @@ public CommandXboxController(int port) { super(port); m_hid = new XboxController(port); } - + /** * Construct an instance of a controller. * diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 2f5b5d81f24..06e86bd0484 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -93,7 +93,7 @@ requires `innerResource` will cancel a running `outerCommand` - but only if `out *currently using* the inner resource at the time. **Effectively, all child commands in v3 are "proxied"**, using the v2 framework's definition, unless -using the built-in ParallelGroup and Sequence compositions or explicitly adding child command +using the built-in ParallelGroup and Sequence compositions or explicitly adding child command requirements to the parent. However, child commands _cannot_ interrupt their parent, even if they share requirements, unlike proxy commands in v2. @@ -177,7 +177,7 @@ co.yield(); // IllegalStateException ## Implementation Details -### Nomenclature +### Nomenclature **Schedule**: Adding a command to a queue in the scheduler, requesting that that command start running in the next call to the scheduler’s `run()` method. @@ -330,7 +330,7 @@ caused by loop timings for deeply nested commands. Scheduler state is serialized using protobuf. The scheduler will send a list of the currently queued commands and a list of the current running commands. Commands are serialized as (id: uint32, parent_id: uint32, name: string, priority: int32, required_resources: string array, -last_time_ms: double, total_time_ms: double). Consumers can use the `id` and `parent_id` attributes +last_time_ms: double, total_time_ms: double). Consumers can use the `id` and `parent_id` attributes to reconstruct the tree structure, if desired. `id` and `parent_id` marginally increase the size of serialized data, but make the schema and deserialization quite simple. From f889a08d24ebc032e7dd384af7dc3bf52d72fa37 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 22:32:32 -0400 Subject: [PATCH 054/153] Add bazel build and DevMain DevMain mostly to match commandsv2 build setup --- BUILD.bazel | 2 + commandsv3/BUILD.bazel | 88 +++++++++++++++++++ commandsv3/generate.bzl | 32 +++++++ .../java/org/wpilib/commands3/DevMain.java | 21 +++++ 4 files changed, 143 insertions(+) create mode 100644 commandsv3/BUILD.bazel create mode 100644 commandsv3/generate.bzl create mode 100644 commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java diff --git a/BUILD.bazel b/BUILD.bazel index d4e60b23656..1b896600b3d 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -45,6 +45,7 @@ write_source_files( "//wpilibj:write_wpilibj", "//wpilibjExamples:write_example_project_list", "//wpilibNewCommands:write_wpilib_new_commands", + "//commandsv3:write_commandsv3", "//wpimath:write_wpimath", "//wpiunits:write_wpiunits", "//wpiutil:write_wpiutil", @@ -88,6 +89,7 @@ publish_all( "//wpilibj:wpilibj-java_publish", "//wpilibNewCommands:wpilibNewCommands-cpp_publish", "//wpilibNewCommands:wpilibNewCommands-java_publish", + "//commandsv3:commandsv3-java_publish", "//wpimath:wpimath-cpp_publish", "//wpimath:wpimath-java_publish", "//wpinet:wpinet-cpp_publish", diff --git a/commandsv3/BUILD.bazel b/commandsv3/BUILD.bazel new file mode 100644 index 00000000000..3355c5e83e9 --- /dev/null +++ b/commandsv3/BUILD.bazel @@ -0,0 +1,88 @@ +load("@allwpilib_pip_deps//:requirements.bzl", "requirement") +load("@aspect_bazel_lib//lib:write_source_files.bzl", "write_source_files") +load("@rules_java//java:defs.bzl", "java_binary") +load("@rules_python//python:defs.bzl", "py_binary") +load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test", "wpilib_java_library") +load("//commandsv3:generate.bzl", "generate_commandsv3") + +py_binary( + name = "generate_hids", + srcs = ["generate_hids.py"], + target_compatible_with = select({ + "@rules_bzlmodrio_toolchains//constraints/is_systemcore:systemcore": ["@platforms//:incompatible"], + "//conditions:default": [], + }), + deps = [requirement("jinja2")], +) + +filegroup( + name = "templates", + srcs = glob(["src/generate/main/**"]) + [ + "//wpilibj:hid_schema", + ], +) + +generate_commandsv3( + name = "generate_commandsv3", +) + +write_source_files( + name = "write_commandsv3", + files = { + "src/generated": ":generate_commandsv3", + }, + suggested_update_target = "//:write_all", + tags = ["pregeneration"], + visibility = ["//visibility:public"], +) + +filegroup( + name = "generated_java", + srcs = glob(["src/generated/main/java/**/*.java"]), +) + +wpilib_java_library( + name = "commandsv3-java", + srcs = glob(["src/main/java/**/*.java"]) + [":generated_java"], + maven_artifact_name = "commandsv3-java", + maven_group_id = "org.wpilib.commands3", + visibility = ["//visibility:public"], + deps = [ + "//cscore:cscore-java", + "//hal:hal-java", + "//ntcore:ntcore-java", + "//wpilibj:wpilibj-java", + "//wpimath:wpimath-java", + "//wpinet:wpinet-java", + "//wpiunits:wpiunits-java", + "//wpiutil:wpiutil-java", + "@maven//:us_hebi_quickbuf_quickbuf_runtime", + ], +) + +wpilib_java_junit5_test( + name = "commandsv3-java-test", + srcs = glob(["**/*.java"]), + deps = [ + ":commandsv3-java", + "//hal:hal-java", + "//ntcore:ntcore-java", + "//wpilibj:wpilibj-java", + "//wpimath:wpimath-java", + "//wpiunits:wpiunits-java", + "//wpiutil:wpiutil-java", + "@maven//:us_hebi_quickbuf_quickbuf_runtime", + ], +) + +java_binary( + name = "DevMain-Java", + srcs = ["src/dev/java/org/wpilib/commands3/DevMain.java"], + main_class = "org.wpilib.commands3.DevMain", + deps = [ + "//hal:hal-java", + "//ntcore:ntcore-java", + "//wpimath:wpimath-java", + "//wpiutil:wpiutil-java", + ], +) diff --git a/commandsv3/generate.bzl b/commandsv3/generate.bzl new file mode 100644 index 00000000000..65e3a6365a7 --- /dev/null +++ b/commandsv3/generate.bzl @@ -0,0 +1,32 @@ +def __generate_commandsv3_impl(ctx): + """ + Custom rule used to create the commandsv3 pre-generated files. See `./README-Bazel.md` for the reasoning. + """ + output_dir = ctx.actions.declare_directory("_gendir") + + args = ctx.actions.args() + args.add("--output_directory", output_dir.path) + args.add("--template_root", "commandsv3/src/generate") + + ctx.actions.run( + inputs = ctx.attr._templates.files, + outputs = [output_dir], + executable = ctx.executable._tool, + arguments = [args], + ) + + return [DefaultInfo(files = depset([output_dir]))] + +generate_commandsv3 = rule( + implementation = __generate_commandsv3_impl, + attrs = { + "_templates": attr.label( + default = Label("//commandsv3:templates"), + ), + "_tool": attr.label( + default = Label("//commandsv3:generate_hids"), + cfg = "exec", + executable = True, + ), + }, +) diff --git a/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java new file mode 100644 index 00000000000..84d763dbe55 --- /dev/null +++ b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java @@ -0,0 +1,21 @@ +// 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 org.wpilib.commands3; + +import edu.wpi.first.hal.HALUtil; +import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.util.CombinedRuntimeLoader; + +public class DevMain { + public static void main(String[] args) { + System.out.println("Commands V3 DevMain"); + + System.out.println(CombinedRuntimeLoader.getPlatformPath()); + System.out.println(NetworkTablesJNI.now()); + System.out.println(HALUtil.getHALRuntimeType()); + } + + private DevMain() {} +} From 9d1e4901bac572b9ed2c300a65d4338611f98f05 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 25 Jul 2025 22:34:35 -0400 Subject: [PATCH 055/153] Bazel linting --- commandsv3/BUILD.bazel | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/commandsv3/BUILD.bazel b/commandsv3/BUILD.bazel index 3355c5e83e9..40e69d30934 100644 --- a/commandsv3/BUILD.bazel +++ b/commandsv3/BUILD.bazel @@ -2,8 +2,8 @@ load("@allwpilib_pip_deps//:requirements.bzl", "requirement") load("@aspect_bazel_lib//lib:write_source_files.bzl", "write_source_files") load("@rules_java//java:defs.bzl", "java_binary") load("@rules_python//python:defs.bzl", "py_binary") -load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test", "wpilib_java_library") load("//commandsv3:generate.bzl", "generate_commandsv3") +load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test", "wpilib_java_library") py_binary( name = "generate_hids", From 6a78627c0ace9f8c1d253e8d58fd243dec099157 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Jul 2025 10:04:55 -0400 Subject: [PATCH 056/153] Fix comment in generated controllers --- commandsv3/src/generate/main/java/commandhid.java.jinja | 2 +- .../java/org/wpilib/commands3/button/CommandPS4Controller.java | 2 +- .../java/org/wpilib/commands3/button/CommandPS5Controller.java | 2 +- .../org/wpilib/commands3/button/CommandStadiaController.java | 2 +- .../java/org/wpilib/commands3/button/CommandXboxController.java | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/commandsv3/src/generate/main/java/commandhid.java.jinja b/commandsv3/src/generate/main/java/commandhid.java.jinja index 777bbcbb70b..65ee942de41 100644 --- a/commandsv3/src/generate/main/java/commandhid.java.jinja +++ b/commandsv3/src/generate/main/java/commandhid.java.jinja @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY {% macro capitalize_first(string) -%} {{ string[0]|capitalize + string[1:] }} {%- endmacro %} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index c67f035a1fe..31272424867 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 0f9e73eba58..6baf2f72b8c 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java index 6317656853d..26ac1f8f62e 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java index c4902c81f37..65f3aba7ed2 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./wpilibNewCommands/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY package org.wpilib.commands3.button; From 017135dadc79a4555161f0c30af13b5a6a0f2897 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Jul 2025 10:05:20 -0400 Subject: [PATCH 057/153] Update frcYear in vendor json --- commandsv3/CommandsV3.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/commandsv3/CommandsV3.json b/commandsv3/CommandsV3.json index 8e79da97c51..a941c3ebfb4 100644 --- a/commandsv3/CommandsV3.json +++ b/commandsv3/CommandsV3.json @@ -3,7 +3,7 @@ "name": "Commands v3", "version": "1.0.0", "uuid": "4decdc05-a056-46cf-9561-39449bbb0130", - "frcYear": "2024", + "frcYear": "2027_alpha1", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ From 6a9c1ecdaaa7c2aa3ee4350416a8de4d2d681e3f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Jul 2025 10:05:39 -0400 Subject: [PATCH 058/153] Remove unneeded javadoc compile options --- commandsv3/build.gradle | 5 ----- 1 file changed, 5 deletions(-) diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index b067af5b1f0..c5c1b883d78 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -30,11 +30,6 @@ dependencies { sourceSets.main.java.srcDir "${projectDir}/src/generated/main/java" sourceSets.main.resources.srcDir "${projectDir}/src/main/proto" -tasks.withType(Javadoc) { - options.addBooleanOption("-enable-preview", true) - options.addStringOption("-release", "21") -} - test { testLogging { outputs.upToDateWhen {false} From 67c4e0b841d36d5c7a9bd1a266355e9fdf59ce90 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Jul 2025 10:11:41 -0400 Subject: [PATCH 059/153] Unmuck snippet formatting --- .../java/org/wpilib/commands3/Command.java | 6 ++--- .../java/org/wpilib/commands3/Coroutine.java | 26 ++++++++++++++----- 2 files changed, 23 insertions(+), 9 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 4cc94c01e9a..a3fdabbab46 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -21,7 +21,7 @@ * command implementation must call {@link Coroutine#yield()} within any periodic * loop. Failure to do so may result in an unrecoverable infinite loop. * - *

{@snippet lang = java: + *

{@snippet lang="java": * // A 2013-style class-based command definition * class ClassBasedCommand extends Command { * public ClassBasedCommand(Subsystem requiredSubsystem) { @@ -267,7 +267,7 @@ default ParallelGroupBuilder until(BooleanSupplier endCondition) { * Starts creating a command sequence, starting from this command and then running the next one. * More commands can be added with the builder before naming and creating the sequence. * - *

{@snippet lang="java" : + *

{@snippet lang="java": * Sequence aThenBThenC = * commandA() * .andThen(commandB()) @@ -286,7 +286,7 @@ default SequenceBuilder andThen(Command next) { * Starts creating a parallel command group, running this command alongside one or more other * commands. The group will exit once every command has finished. * - *

{@snippet lang="java" : + *

{@snippet lang="java": * ParallelGroup abc = * commandA() * .alongWith(commandB(), commandC()) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 7e7a91625a2..0d088390fdf 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -78,9 +78,17 @@ public void park() { * parent command cancels it. The parent command will continue executing while the forked command * runs, and can resync with the forked command using {@link #await(Command)}. * - *

{@snippet lang = java: Command example() { return Command.noRequirements(coroutine -> { - * Command inner = ...; coroutine.fork(inner); // ... do more things // then sync back up with the - * inner command coroutine.await(inner); }).named("Example"); } } + *

{@snippet lang="java": + * Command example() { + * return Command.noRequirements(coroutine -> { + * Command inner = ...; + * coroutine.fork(inner); + * // ... do more things + * // then sync back up with the inner command + * coroutine.await(inner); + * }).named("Example"); + * } + * } * * @param commands The commands to fork. */ @@ -228,9 +236,15 @@ private static void validateNoConflicts(Collection commands) { * *

For example, a basic autonomous routine that drives straight for 5 seconds: * - *

{@snippet lang = java : Command timedDrive() { return drivebase.run(coroutine -> { - * drivebase.tankDrive(1, 1); coroutine.wait(Seconds.of(5)); drivebase.stop(); }).named("Timed - * Drive"); } } + *

{@snippet lang="java": + * Command timedDrive() { + * return drivebase.run(coroutine -> { + * drivebase.tankDrive(1, 1); + * coroutine.wait(Seconds.of(5)); + * drivebase.stop(); + * }).named("Timed Drive"); + * } + * } * * @param duration the duration of time to wait */ From c9c5a1f63cf0f446f0f7288bd89f3b32bf044f4b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 26 Jul 2025 10:19:31 -0400 Subject: [PATCH 060/153] CMake build updates --- commandsv3/CMakeLists.txt | 24 ++++++++++-------------- 1 file changed, 10 insertions(+), 14 deletions(-) diff --git a/commandsv3/CMakeLists.txt b/commandsv3/CMakeLists.txt index 4c9fe0f950a..d37bff6b4df 100644 --- a/commandsv3/CMakeLists.txt +++ b/commandsv3/CMakeLists.txt @@ -5,15 +5,14 @@ include(CompileWarnings) include(AddTest) if(WITH_JAVA) - find_package(Java REQUIRED) include(UseJava) - set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked") - file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) + file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) add_jar( commandsv3_jar ${JAVA_SOURCES} INCLUDE_JARS + datalog_jar hal_jar ntcore_jar cscore_jar @@ -23,6 +22,7 @@ if(WITH_JAVA) wpiutil_jar wpilibj_jar OUTPUT_NAME commandsv3 + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) install_jar(commandsv3_jar DESTINATION ${java_lib_dest}) @@ -34,22 +34,18 @@ if(WITH_JAVA) endif() if(WITH_JAVA_SOURCE) - find_package(Java REQUIRED) include(UseJava) - file(GLOB commandsv3_SOURCES src/main/java/edu/wpi/first/wpilibj/commandsv3/*.java) - file(GLOB commandsv3_BUTTON_SOURCES src/main/java/edu/wpi/first/wpilibj2/command/button*.java) - add_jar( + include(CreateSourceJar) + add_source_jar( commandsv3_src_jar - RESOURCES - NAMESPACE "edu/wpi/first/wpilibj/commandsv3" ${commandsv3_SOURCES} - NAMESPACE "edu/wpi/first/wpilibj/commandsv3/button" ${commandsv3_BUTTON_SOURCES} + BASE_DIRECTORIES + ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java + ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java OUTPUT_NAME commandsv3-sources + OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) - - get_property(commandsv3_SRC_JAR_FILE TARGET commandsv3_src_jar PROPERTY JAR_FILE) - install(FILES ${commandsv3_SRC_JAR_FILE} DESTINATION "${java_lib_dest}") - set_property(TARGET commandsv3_src_jar PROPERTY FOLDER "java") + install_jar(commandsv3_src_jar DESTINATION ${java_lib_dest}) endif() install(TARGETS commandsv3 EXPORT commandsv3) From 21806f7b3e98b680764a6c1fec6b5ec7cd81a49a Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 27 Jul 2025 15:08:00 -0400 Subject: [PATCH 061/153] DevMain linting --- commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java index 84d763dbe55..0b8cfaf30c7 100644 --- a/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java +++ b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java @@ -8,7 +8,9 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.util.CombinedRuntimeLoader; +/** Dev main. */ public class DevMain { + /** Main entry point. */ public static void main(String[] args) { System.out.println("Commands V3 DevMain"); From dafbe3265df615cf53a66b48805c5c70ca83af60 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 27 Jul 2025 15:08:26 -0400 Subject: [PATCH 062/153] Apply bazel patch from PJ to generate protobuf files --- commandsv3/generate.bzl | 13 ++++++++++ commandsv3/generate_hids.py | 47 +++++++++++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) diff --git a/commandsv3/generate.bzl b/commandsv3/generate.bzl index 65e3a6365a7..fe89fcb3cd7 100644 --- a/commandsv3/generate.bzl +++ b/commandsv3/generate.bzl @@ -7,12 +7,15 @@ def __generate_commandsv3_impl(ctx): args = ctx.actions.args() args.add("--output_directory", output_dir.path) args.add("--template_root", "commandsv3/src/generate") + args.add("--protoc", ctx.executable._protoc) + args.add("--quickbuf_plugin", ctx.executable._quickbuf) ctx.actions.run( inputs = ctx.attr._templates.files, outputs = [output_dir], executable = ctx.executable._tool, arguments = [args], + tools = [ctx.executable._protoc, ctx.executable._quickbuf], ) return [DefaultInfo(files = depset([output_dir]))] @@ -28,5 +31,15 @@ generate_commandsv3 = rule( cfg = "exec", executable = True, ), + "_protoc": attr.label( + default = Label("@com_google_protobuf//:protoc"), + cfg = "exec", + executable = True, + ), + "_quickbuf": attr.label( + default = Label("//:quickbuf_protoc"), + cfg = "exec", + executable = True, + ), }, ) diff --git a/commandsv3/generate_hids.py b/commandsv3/generate_hids.py index f232556fad4..fb71ff79601 100755 --- a/commandsv3/generate_hids.py +++ b/commandsv3/generate_hids.py @@ -5,6 +5,7 @@ # the WPILib BSD license file in the root directory of this project. import argparse +import subprocess import json from pathlib import Path @@ -15,6 +16,7 @@ def write_controller_file(output_dir: Path, controller_name: str, contents: str) output_dir.mkdir(parents=True, exist_ok=True) output_file = output_dir / controller_name output_file.write_text(contents, encoding="utf-8", newline="\n") + print("Writing to ", output_file) def generate_hids(output_directory: Path, template_directory: Path, schema_file: Path): @@ -36,6 +38,34 @@ def generate_hids(output_directory: Path, template_directory: Path, schema_file: write_controller_file(root_path, controllerName, output) +def generate_quickbuf( + protoc, quickbuf_plugin: Path, output_directory: Path, proto_dir: Path +): + proto_files = proto_dir.glob("*.proto") + for path in proto_files: + absolute_filename = path.absolute() + subprocess.check_call( + [ + protoc, + f"--plugin=protoc-gen-quickbuf={quickbuf_plugin}", + f"--quickbuf_out=gen_descriptors=true:{output_directory.absolute()}", + f"-I{absolute_filename.parent}", + absolute_filename, + ] + ) + java_files = (output_directory / "org/wpilib/commands3/proto").glob("*.java") + for java_file in java_files: + with (java_file).open(encoding="utf-8") as f: + content = f.read() + + java_file.write_text( + "// Copyright (c) FIRST and other WPILib contributors.\n// Open Source Software; you can modify and/or share it under the terms of\n// the WPILib BSD license file in the root directory of this project.\n" + + content, + encoding="utf-8", + newline="\n", + ) + + def main(): script_path = Path(__file__).resolve() dirname = script_path.parent @@ -59,9 +89,26 @@ def main(): default="wpilibj/src/generate/hids.json", type=Path, ) + parser.add_argument( + "--protoc", + help="Protoc executable command", + default="protoc", + ) + parser.add_argument( + "--quickbuf_plugin", + help="Path to the quickbuf protoc plugin", + required=True, + ) + parser.add_argument( + "--proto_directory", + help="Optional. If set, will use this directory to glob for protobuf files", + default=dirname / "src/main/proto", + type=Path, + ) args = parser.parse_args() generate_hids(args.output_directory, args.template_root, args.schema_file) + generate_quickbuf(args.protoc, args.quickbuf_plugin, args.output_directory / "main/java", args.proto_directory) if __name__ == "__main__": From d11d9ade8b12f15619f5e6684ceef8d9a02b6ba1 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 19:36:46 -0400 Subject: [PATCH 063/153] Cancel commands when binding scopes become inactive Add design doc details for binding scopes --- .../org/wpilib/commands3/BindingScope.java | 2 +- .../java/org/wpilib/commands3/Trigger.java | 35 ++++++++++++------ .../org/wpilib/commands3/TriggerTest.java | 22 ++++++++++++ design-docs/commands-v3.md | 36 +++++++++++++++++++ 4 files changed, 83 insertions(+), 12 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java index 2aea39d2caa..0b2077ca0ad 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java @@ -8,7 +8,7 @@ * A scope for when a binding is live. Bindings tied to a scope must be deleted when the scope * becomes inactive. */ -sealed interface BindingScope { +interface BindingScope { /** * Checks if the scope is active. Bindings for inactive scopes are removed from the scheduler. * diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index d0a5cd02b27..0ab20ecbcca 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -270,11 +270,19 @@ private Signal signal() { } } - /** Removes bindings in inactive scopes. */ + /** Removes bindings in inactive scopes. Running commands tied to those bindings are cancelled. */ private void clearStaleBindings() { m_bindings.forEach( (_bindingType, bindings) -> { - bindings.removeIf(binding -> !binding.scope().active()); + for (var iterator = bindings.iterator(); iterator.hasNext(); ) { + var binding = iterator.next(); + if (binding.scope().active()) { + continue; + } + + iterator.remove(); + m_scheduler.cancel(binding.command()); + } }); } @@ -318,6 +326,19 @@ private void toggleBindings(BindingType bindingType) { }); } + // package-private for testing + void addBinding(BindingScope scope, BindingType bindingType, Command command) { + Throwable t = new Throwable("Dummy error to get the binding trace"); + StackTraceElement[] frames = t.getStackTrace(); + + m_bindings + .computeIfAbsent(bindingType, _k -> new ArrayList<>()) + .add(new Binding(scope, bindingType, command, frames)); + + // Ensure this trigger is bound to the event loop. NOP if already bound + m_loop.bind(m_eventLoopCallback); + } + private void addBinding(BindingType bindingType, Command command) { BindingScope scope = switch (m_scheduler.currentCommand()) { @@ -331,14 +352,6 @@ private void addBinding(BindingType bindingType, Command command) { } }; - Throwable t = new Throwable("Dummy error to get the binding trace"); - StackTraceElement[] frames = t.getStackTrace(); - - m_bindings - .computeIfAbsent(bindingType, _k -> new ArrayList<>()) - .add(new Binding(scope, bindingType, command, frames)); - - // Ensure this trigger is bound to the event loop. NOP if already bound - m_loop.bind(m_eventLoopCallback); + addBinding(scope, bindingType, command); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index 937b98cad60..18ac8c4e492 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -163,4 +163,26 @@ void commandScoping() { m_scheduler.run(); assertFalse(innerRan.get(), "Trigger should not have fired again"); } + + @Test + void scopeGoingInactiveCancelsBoundCommand() { + var activeScope = new AtomicBoolean(true); + BindingScope scope = activeScope::get; + + var triggerSignal = new AtomicBoolean(false); + var trigger = new Trigger(m_scheduler, triggerSignal::get); + + var command = Command.noRequirements(Coroutine::park).named("Command"); + trigger.addBinding(scope, BindingType.RUN_WHILE_HIGH, command); + + triggerSignal.set(true); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command), "Command should have started when triggered"); + + activeScope.set(false); + m_scheduler.run(); + assertFalse( + m_scheduler.isRunning(command), + "Command should have been cancelled when scope became inactive"); + } } diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 06e86bd0484..a03b2191f5e 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -117,6 +117,42 @@ its children, even if some of those children are suspendable. Suspending a command that already has suspended children will still suspend everything; however, upon resume, those suspended children will remain suspended. +### Inner Triggers + +Teams often want to use triggers only within the scope of certain commands. For example, running an +autonomous mode that follows a particular path, and do certain actions when various points along the +path are reached, but not have those actions be bound to globally visible triggers that may fire at +other times during a match. In v2, such triggers need to be composed either a with a function that +checks if a valid autonomous mode is running or with the same trigger that can cause that routine to +run. This leads to many, many triggers being defined in robot programs and makes it difficult to +understand when all those triggers may be used. + +The v3 framework will track the scopes in which trigger bindings are created, and automatically +delete those bindings (and cancel any running commands bound to them) when their scopes become +inactive. Users who manually schedule a command create a binding in a "global" scope that is always +active. Binding commands to a trigger, however, will use whatever the narrowest available scope is +at the time - creating a binding inside a running command will be scoped to that command's lifetime; +creating a binding outside a command (for example, in a main Robot class constructor) will also use +the "global" scope. + +```java +void bindDriveButtons() { + // Globally bound and will always be active + controller.a().onTrue(...) +} + +Trigger atScoringPosition = new Trigger(() -> getPosition().isNear(kScoringPosition)); + +Command autonomous() { + return Command.noRequirements(coroutine -> { + // This binding only exists while the autonomous command is running + atScoringPosition.onTrue(score()); + + coroutine.await(driveToScoringPosition()); + }).named("Autonomous"); +} +``` + ### Improved Transparency The v2 commands framework only runs top-level commands in the scheduler; commands nested within a From db62193061f1995ea11c2d92cee83e13eb92bef3 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 20:10:54 -0400 Subject: [PATCH 064/153] Lint --- commandsv3/generate_hids.py | 9 +++++++-- .../src/dev/java/org/wpilib/commands3/DevMain.java | 2 +- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/commandsv3/generate_hids.py b/commandsv3/generate_hids.py index fb71ff79601..d2b35322c7c 100755 --- a/commandsv3/generate_hids.py +++ b/commandsv3/generate_hids.py @@ -5,8 +5,8 @@ # the WPILib BSD license file in the root directory of this project. import argparse -import subprocess import json +import subprocess from pathlib import Path from jinja2 import Environment, FileSystemLoader @@ -108,7 +108,12 @@ def main(): args = parser.parse_args() generate_hids(args.output_directory, args.template_root, args.schema_file) - generate_quickbuf(args.protoc, args.quickbuf_plugin, args.output_directory / "main/java", args.proto_directory) + generate_quickbuf( + args.protoc, + args.quickbuf_plugin, + args.output_directory / "main/java", + args.proto_directory, + ) if __name__ == "__main__": diff --git a/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java index 0b8cfaf30c7..8a92b7b09d8 100644 --- a/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java +++ b/commandsv3/src/dev/java/org/wpilib/commands3/DevMain.java @@ -9,7 +9,7 @@ import edu.wpi.first.util.CombinedRuntimeLoader; /** Dev main. */ -public class DevMain { +public final class DevMain { /** Main entry point. */ public static void main(String[] args) { System.out.println("Commands V3 DevMain"); From 5130af29c28940c06f5d3b84bc969ad90e18062c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 20:34:56 -0400 Subject: [PATCH 065/153] Lint --- design-docs/commands-v3.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index a03b2191f5e..8cb40b12876 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -142,7 +142,7 @@ void bindDriveButtons() { } Trigger atScoringPosition = new Trigger(() -> getPosition().isNear(kScoringPosition)); - + Command autonomous() { return Command.noRequirements(coroutine -> { // This binding only exists while the autonomous command is running From e6f63dacefdc6b04d3b9aea48e18830886d93798 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 21:04:41 -0400 Subject: [PATCH 066/153] Bazel linting --- commandsv3/generate.bzl | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/commandsv3/generate.bzl b/commandsv3/generate.bzl index fe89fcb3cd7..34b81ab54b8 100644 --- a/commandsv3/generate.bzl +++ b/commandsv3/generate.bzl @@ -23,14 +23,6 @@ def __generate_commandsv3_impl(ctx): generate_commandsv3 = rule( implementation = __generate_commandsv3_impl, attrs = { - "_templates": attr.label( - default = Label("//commandsv3:templates"), - ), - "_tool": attr.label( - default = Label("//commandsv3:generate_hids"), - cfg = "exec", - executable = True, - ), "_protoc": attr.label( default = Label("@com_google_protobuf//:protoc"), cfg = "exec", @@ -41,5 +33,13 @@ generate_commandsv3 = rule( cfg = "exec", executable = True, ), + "_templates": attr.label( + default = Label("//commandsv3:templates"), + ), + "_tool": attr.label( + default = Label("//commandsv3:generate_hids"), + cfg = "exec", + executable = True, + ), }, ) From cb51791910750929030658a25d6796a6abcc580b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 21:11:51 -0400 Subject: [PATCH 067/153] Regenerate protobuf files They're ignored by spotless now, and need to not change after generation for bazel build checks to pass --- .../commands3/proto/ProtobufCommand.java | 433 +++++++----------- .../proto/ProtobufRequireableResource.java | 97 ++-- .../commands3/proto/ProtobufScheduler.java | 241 ++++------ .../org/wpilib/commands3/proto/Scheduler.java | 104 ++--- 4 files changed, 348 insertions(+), 527 deletions(-) diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java index 470720ae428..5cda3055792 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java @@ -1,7 +1,6 @@ // 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. - // Code generated by protocol buffer compiler. Do not edit! package org.wpilib.commands3.proto; @@ -19,14 +18,14 @@ import us.hebi.quickbuf.RepeatedMessage; import us.hebi.quickbuf.Utf8String; -/** Protobuf type {@code ProtobufCommand} */ +/** + * Protobuf type {@code ProtobufCommand} + */ @SuppressWarnings("hiding") public final class ProtobufCommand extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; /** - * - * *

    *  How much time the command took to execute in its most recent run.
    *  Only included in a message for an actively running command.
@@ -37,8 +36,6 @@ public final class ProtobufCommand extends ProtoMessage impleme
   private double lastTimeMs;
 
   /**
-   *
-   *
    * 
    *  How long the command has taken to run, in aggregate.
    *  Only included in a message for an actively running command.
@@ -49,8 +46,6 @@ public final class ProtobufCommand extends ProtoMessage impleme
   private double totalTimeMs;
 
   /**
-   *
-   *
    * 
    *  The priority level of the command.
    * 
@@ -60,8 +55,6 @@ public final class ProtobufCommand extends ProtoMessage impleme private int priority; /** - * - * *
    *  A unique ID for the command.
    *  Different invocations of the same command object have different IDs.
@@ -72,8 +65,6 @@ public final class ProtobufCommand extends ProtoMessage impleme
   private int id;
 
   /**
-   *
-   *
    * 
    *  The ID of the parent command.
    *  Not included in the message for top-level commands.
@@ -84,8 +75,6 @@ public final class ProtobufCommand extends ProtoMessage impleme
   private int parentId;
 
   /**
-   *
-   *
    * 
    *  The name of the command.
    * 
@@ -95,18 +84,16 @@ public final class ProtobufCommand extends ProtoMessage impleme private final Utf8String name = Utf8String.newEmptyInstance(); /** - * - * *
    *  The resources required by the command.
    * 
* * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; */ - private final RepeatedMessage requirements = - RepeatedMessage.newEmptyInstance(ProtobufRequireableResource.getFactory()); + private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufRequireableResource.getFactory()); - private ProtobufCommand() {} + private ProtobufCommand() { + } /** * @return a new empty instance of {@code ProtobufCommand} @@ -116,15 +103,12 @@ public static ProtobufCommand newInstance() { } /** - * - * *
    *  How much time the command took to execute in its most recent run.
    *  Only included in a message for an actively running command.
    * 
* * optional double last_time_ms = 6; - * * @return whether the lastTimeMs field is set */ public boolean hasLastTimeMs() { @@ -132,15 +116,12 @@ public boolean hasLastTimeMs() { } /** - * - * *
    *  How much time the command took to execute in its most recent run.
    *  Only included in a message for an actively running command.
    * 
* * optional double last_time_ms = 6; - * * @return this */ public ProtobufCommand clearLastTimeMs() { @@ -150,15 +131,12 @@ public ProtobufCommand clearLastTimeMs() { } /** - * - * *
    *  How much time the command took to execute in its most recent run.
    *  Only included in a message for an actively running command.
    * 
* * optional double last_time_ms = 6; - * * @return the lastTimeMs */ public double getLastTimeMs() { @@ -166,15 +144,12 @@ public double getLastTimeMs() { } /** - * - * *
    *  How much time the command took to execute in its most recent run.
    *  Only included in a message for an actively running command.
    * 
* * optional double last_time_ms = 6; - * * @param value the lastTimeMs to set * @return this */ @@ -185,15 +160,12 @@ public ProtobufCommand setLastTimeMs(final double value) { } /** - * - * *
    *  How long the command has taken to run, in aggregate.
    *  Only included in a message for an actively running command.
    * 
* * optional double total_time_ms = 7; - * * @return whether the totalTimeMs field is set */ public boolean hasTotalTimeMs() { @@ -201,15 +173,12 @@ public boolean hasTotalTimeMs() { } /** - * - * *
    *  How long the command has taken to run, in aggregate.
    *  Only included in a message for an actively running command.
    * 
* * optional double total_time_ms = 7; - * * @return this */ public ProtobufCommand clearTotalTimeMs() { @@ -219,15 +188,12 @@ public ProtobufCommand clearTotalTimeMs() { } /** - * - * *
    *  How long the command has taken to run, in aggregate.
    *  Only included in a message for an actively running command.
    * 
* * optional double total_time_ms = 7; - * * @return the totalTimeMs */ public double getTotalTimeMs() { @@ -235,15 +201,12 @@ public double getTotalTimeMs() { } /** - * - * *
    *  How long the command has taken to run, in aggregate.
    *  Only included in a message for an actively running command.
    * 
* * optional double total_time_ms = 7; - * * @param value the totalTimeMs to set * @return this */ @@ -254,14 +217,11 @@ public ProtobufCommand setTotalTimeMs(final double value) { } /** - * - * *
    *  The priority level of the command.
    * 
* * optional int32 priority = 4; - * * @return whether the priority field is set */ public boolean hasPriority() { @@ -269,14 +229,11 @@ public boolean hasPriority() { } /** - * - * *
    *  The priority level of the command.
    * 
* * optional int32 priority = 4; - * * @return this */ public ProtobufCommand clearPriority() { @@ -286,14 +243,11 @@ public ProtobufCommand clearPriority() { } /** - * - * *
    *  The priority level of the command.
    * 
* * optional int32 priority = 4; - * * @return the priority */ public int getPriority() { @@ -301,14 +255,11 @@ public int getPriority() { } /** - * - * *
    *  The priority level of the command.
    * 
* * optional int32 priority = 4; - * * @param value the priority to set * @return this */ @@ -319,15 +270,12 @@ public ProtobufCommand setPriority(final int value) { } /** - * - * *
    *  A unique ID for the command.
    *  Different invocations of the same command object have different IDs.
    * 
* * optional uint32 id = 1; - * * @return whether the id field is set */ public boolean hasId() { @@ -335,15 +283,12 @@ public boolean hasId() { } /** - * - * *
    *  A unique ID for the command.
    *  Different invocations of the same command object have different IDs.
    * 
* * optional uint32 id = 1; - * * @return this */ public ProtobufCommand clearId() { @@ -353,15 +298,12 @@ public ProtobufCommand clearId() { } /** - * - * *
    *  A unique ID for the command.
    *  Different invocations of the same command object have different IDs.
    * 
* * optional uint32 id = 1; - * * @return the id */ public int getId() { @@ -369,15 +311,12 @@ public int getId() { } /** - * - * *
    *  A unique ID for the command.
    *  Different invocations of the same command object have different IDs.
    * 
* * optional uint32 id = 1; - * * @param value the id to set * @return this */ @@ -388,15 +327,12 @@ public ProtobufCommand setId(final int value) { } /** - * - * *
    *  The ID of the parent command.
    *  Not included in the message for top-level commands.
    * 
* * optional uint32 parent_id = 2; - * * @return whether the parentId field is set */ public boolean hasParentId() { @@ -404,15 +340,12 @@ public boolean hasParentId() { } /** - * - * *
    *  The ID of the parent command.
    *  Not included in the message for top-level commands.
    * 
* * optional uint32 parent_id = 2; - * * @return this */ public ProtobufCommand clearParentId() { @@ -422,15 +355,12 @@ public ProtobufCommand clearParentId() { } /** - * - * *
    *  The ID of the parent command.
    *  Not included in the message for top-level commands.
    * 
* * optional uint32 parent_id = 2; - * * @return the parentId */ public int getParentId() { @@ -438,15 +368,12 @@ public int getParentId() { } /** - * - * *
    *  The ID of the parent command.
    *  Not included in the message for top-level commands.
    * 
* * optional uint32 parent_id = 2; - * * @param value the parentId to set * @return this */ @@ -457,14 +384,11 @@ public ProtobufCommand setParentId(final int value) { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @return whether the name field is set */ public boolean hasName() { @@ -472,14 +396,11 @@ public boolean hasName() { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @return this */ public ProtobufCommand clearName() { @@ -489,14 +410,11 @@ public ProtobufCommand clearName() { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @return the name */ public String getName() { @@ -504,14 +422,11 @@ public String getName() { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @return internal {@code Utf8String} representation of name for reading */ public Utf8String getNameBytes() { @@ -519,14 +434,11 @@ public Utf8String getNameBytes() { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @return internal {@code Utf8String} representation of name for modifications */ public Utf8String getMutableNameBytes() { @@ -535,14 +447,11 @@ public Utf8String getMutableNameBytes() { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @param value the name to set * @return this */ @@ -553,14 +462,11 @@ public ProtobufCommand setName(final CharSequence value) { } /** - * - * *
    *  The name of the command.
    * 
* * optional string name = 3; - * * @param value the name to set * @return this */ @@ -571,14 +477,11 @@ public ProtobufCommand setName(final Utf8String value) { } /** - * - * *
    *  The resources required by the command.
    * 
* * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; - * * @return whether the requirements field is set */ public boolean hasRequirements() { @@ -586,14 +489,11 @@ public boolean hasRequirements() { } /** - * - * *
    *  The resources required by the command.
    * 
* * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; - * * @return this */ public ProtobufCommand clearRequirements() { @@ -603,17 +503,16 @@ public ProtobufCommand clearRequirements() { } /** - * - * *
    *  The resources required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method - * returns the internal storage object without modifying any has state. The returned object should - * not be modified and be treated as read-only. + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. * - *

Use {@link #getMutableRequirements()} if you want to modify it. + * Use {@link #getMutableRequirements()} if you want to modify it. * * @return internal storage object for reading */ @@ -622,16 +521,15 @@ public RepeatedMessage getRequirements() { } /** - * - * *

    *  The resources required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; This method - * returns the internal storage object and sets the corresponding has state. The returned object - * will become part of this message and its contents may be modified as long as the has state is - * not cleared. + * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. * * @return internal storage object for modifications */ @@ -641,14 +539,11 @@ public RepeatedMessage getMutableRequirements() { } /** - * - * *
    *  The resources required by the command.
    * 
* * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; - * * @param value the requirements to add * @return this */ @@ -659,14 +554,11 @@ public ProtobufCommand addRequirements(final ProtobufRequireableResource value) } /** - * - * *
    *  The resources required by the command.
    * 
* * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; - * * @param values the requirements to add * @return this */ @@ -761,13 +653,13 @@ public boolean equals(Object o) { } ProtobufCommand other = (ProtobufCommand) o; return bitField0_ == other.bitField0_ - && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) - && (!hasTotalTimeMs() || ProtoUtil.isEqual(totalTimeMs, other.totalTimeMs)) - && (!hasPriority() || priority == other.priority) - && (!hasId() || id == other.id) - && (!hasParentId() || parentId == other.parentId) - && (!hasName() || name.equals(other.name)) - && (!hasRequirements() || requirements.equals(other.requirements)); + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) + && (!hasTotalTimeMs() || ProtoUtil.isEqual(totalTimeMs, other.totalTimeMs)) + && (!hasPriority() || priority == other.priority) + && (!hasId() || id == other.id) + && (!hasParentId() || parentId == other.parentId) + && (!hasName() || name.equals(other.name)) + && (!hasRequirements() || requirements.equals(other.requirements)); } @Override @@ -838,87 +730,78 @@ public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { int tag = input.readTag(); while (true) { switch (tag) { - case 49: - { - // lastTimeMs - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000002; - tag = input.readTag(); - if (tag != 57) { - break; - } + case 49: { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 57) { + break; } - case 57: - { - // totalTimeMs - totalTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 32) { - break; - } + } + case 57: { + // totalTimeMs + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 32) { + break; } - case 32: - { - // priority - priority = input.readInt32(); - bitField0_ |= 0x00000008; - tag = input.readTag(); - if (tag != 8) { - break; - } + } + case 32: { + // priority + priority = input.readInt32(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 8) { + break; } - case 8: - { - // id - id = input.readUInt32(); - bitField0_ |= 0x00000010; - tag = input.readTag(); - if (tag != 16) { - break; - } + } + case 8: { + // id + id = input.readUInt32(); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 16) { + break; } - case 16: - { - // parentId - parentId = input.readUInt32(); - bitField0_ |= 0x00000004; - tag = input.readTag(); - if (tag != 26) { - break; - } + } + case 16: { + // parentId + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 26) { + break; } - case 26: - { - // name - input.readString(name); - bitField0_ |= 0x00000020; - tag = input.readTag(); - if (tag != 42) { - break; - } + } + case 26: { + // name + input.readString(name); + bitField0_ |= 0x00000020; + tag = input.readTag(); + if (tag != 42) { + break; } - case 42: - { - // requirements - tag = input.readRepeatedMessage(requirements, tag); - bitField0_ |= 0x00000040; - if (tag != 0) { - break; - } + } + case 42: { + // requirements + tag = input.readRepeatedMessage(requirements, tag); + bitField0_ |= 0x00000040; + if (tag != 0) { + break; } - case 0: - { + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { return this; } - default: - { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } + tag = input.readTag(); + break; + } } } } @@ -958,97 +841,89 @@ public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { while (!input.isAtEnd()) { switch (input.readFieldHash()) { case 1958056841: - case -740797521: - { - if (input.isAtField(FieldNames.lastTimeMs)) { - if (!input.trySkipNullValue()) { - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000002; - } - } else { - input.skipUnknownField(); + case -740797521: { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; } - break; + } else { + input.skipUnknownField(); } + break; + } case -717217353: - case 1006112349: - { - if (input.isAtField(FieldNames.totalTimeMs)) { - if (!input.trySkipNullValue()) { - totalTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); + case 1006112349: { + if (input.isAtField(FieldNames.totalTimeMs)) { + if (!input.trySkipNullValue()) { + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; } - break; + } else { + input.skipUnknownField(); } - case -1165461084: - { - if (input.isAtField(FieldNames.priority)) { - if (!input.trySkipNullValue()) { - priority = input.readInt32(); - bitField0_ |= 0x00000008; - } - } else { - input.skipUnknownField(); + break; + } + case -1165461084: { + if (input.isAtField(FieldNames.priority)) { + if (!input.trySkipNullValue()) { + priority = input.readInt32(); + bitField0_ |= 0x00000008; } - break; + } else { + input.skipUnknownField(); } - case 3355: - { - if (input.isAtField(FieldNames.id)) { - if (!input.trySkipNullValue()) { - id = input.readUInt32(); - bitField0_ |= 0x00000010; - } - } else { - input.skipUnknownField(); + break; + } + case 3355: { + if (input.isAtField(FieldNames.id)) { + if (!input.trySkipNullValue()) { + id = input.readUInt32(); + bitField0_ |= 0x00000010; } - break; + } else { + input.skipUnknownField(); } + break; + } case 1175162725: - case 2070327504: - { - if (input.isAtField(FieldNames.parentId)) { - if (!input.trySkipNullValue()) { - parentId = input.readUInt32(); - bitField0_ |= 0x00000004; - } - } else { - input.skipUnknownField(); + case 2070327504: { + if (input.isAtField(FieldNames.parentId)) { + if (!input.trySkipNullValue()) { + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; } - break; + } else { + input.skipUnknownField(); } - case 3373707: - { - if (input.isAtField(FieldNames.name)) { - if (!input.trySkipNullValue()) { - input.readString(name); - bitField0_ |= 0x00000020; - } - } else { - input.skipUnknownField(); + break; + } + case 3373707: { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000020; } - break; + } else { + input.skipUnknownField(); } - case -1619874672: - { - if (input.isAtField(FieldNames.requirements)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(requirements); - bitField0_ |= 0x00000040; - } - } else { - input.skipUnknownField(); + break; + } + case -1619874672: { + if (input.isAtField(FieldNames.requirements)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(requirements); + bitField0_ |= 0x00000040; } - break; - } - default: - { + } else { input.skipUnknownField(); - break; } + break; + } + default: { + input.skipUnknownField(); + break; + } } } input.endObject(); @@ -1100,7 +975,9 @@ public ProtobufCommand create() { } } - /** Contains name constants used for serializing JSON */ + /** + * Contains name constants used for serializing JSON + */ static class FieldNames { static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java index 1fa523208ff..d4430c4fb63 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java @@ -1,7 +1,6 @@ // 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. - // Code generated by protocol buffer compiler. Do not edit! package org.wpilib.commands3.proto; @@ -17,16 +16,20 @@ import us.hebi.quickbuf.ProtoSource; import us.hebi.quickbuf.Utf8String; -/** Protobuf type {@code ProtobufRequireableResource} */ +/** + * Protobuf type {@code ProtobufRequireableResource} + */ @SuppressWarnings("hiding") -public final class ProtobufRequireableResource extends ProtoMessage - implements Cloneable { +public final class ProtobufRequireableResource extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; - /** optional string name = 1; */ + /** + * optional string name = 1; + */ private final Utf8String name = Utf8String.newEmptyInstance(); - private ProtobufRequireableResource() {} + private ProtobufRequireableResource() { + } /** * @return a new empty instance of {@code ProtobufRequireableResource} @@ -37,7 +40,6 @@ public static ProtobufRequireableResource newInstance() { /** * optional string name = 1; - * * @return whether the name field is set */ public boolean hasName() { @@ -46,7 +48,6 @@ public boolean hasName() { /** * optional string name = 1; - * * @return this */ public ProtobufRequireableResource clearName() { @@ -57,7 +58,6 @@ public ProtobufRequireableResource clearName() { /** * optional string name = 1; - * * @return the name */ public String getName() { @@ -66,7 +66,6 @@ public String getName() { /** * optional string name = 1; - * * @return internal {@code Utf8String} representation of name for reading */ public Utf8String getNameBytes() { @@ -75,7 +74,6 @@ public Utf8String getNameBytes() { /** * optional string name = 1; - * * @return internal {@code Utf8String} representation of name for modifications */ public Utf8String getMutableNameBytes() { @@ -85,7 +83,6 @@ public Utf8String getMutableNameBytes() { /** * optional string name = 1; - * * @param value the name to set * @return this */ @@ -97,7 +94,6 @@ public ProtobufRequireableResource setName(final CharSequence value) { /** * optional string name = 1; - * * @param value the name to set * @return this */ @@ -160,7 +156,8 @@ public boolean equals(Object o) { return false; } ProtobufRequireableResource other = (ProtobufRequireableResource) o; - return bitField0_ == other.bitField0_ && (!hasName() || name.equals(other.name)); + return bitField0_ == other.bitField0_ + && (!hasName() || name.equals(other.name)); } @Override @@ -187,28 +184,25 @@ public ProtobufRequireableResource mergeFrom(final ProtoSource input) throws IOE int tag = input.readTag(); while (true) { switch (tag) { - case 10: - { - // name - input.readString(name); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 0) { - break; - } + case 10: { + // name + input.readString(name); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; } - case 0: - { + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { return this; } - default: - { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } + tag = input.readTag(); + break; + } } } } @@ -229,23 +223,21 @@ public ProtobufRequireableResource mergeFrom(final JsonSource input) throws IOEx } while (!input.isAtEnd()) { switch (input.readFieldHash()) { - case 3373707: - { - if (input.isAtField(FieldNames.name)) { - if (!input.trySkipNullValue()) { - input.readString(name); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); + case 3373707: { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000001; } - break; - } - default: - { + } else { input.skipUnknownField(); - break; } + break; + } + default: { + input.skipUnknownField(); + break; + } } } input.endObject(); @@ -262,8 +254,8 @@ public boolean isEmpty() { return ((bitField0_) == 0); } - public static ProtobufRequireableResource parseFrom(final byte[] data) - throws InvalidProtocolBufferException { + public static ProtobufRequireableResource parseFrom(final byte[] data) throws + InvalidProtocolBufferException { return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), data).checkInitialized(); } @@ -289,8 +281,7 @@ public static Descriptors.Descriptor getDescriptor() { return Scheduler.wpi_proto_ProtobufRequireableResource_descriptor; } - private enum ProtobufRequireableResourceFactory - implements MessageFactory { + private enum ProtobufRequireableResourceFactory implements MessageFactory { INSTANCE; @Override @@ -299,7 +290,9 @@ public ProtobufRequireableResource create() { } } - /** Contains name constants used for serializing JSON */ + /** + * Contains name constants used for serializing JSON + */ static class FieldNames { static final FieldName name = FieldName.forField("name"); } diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java index 5d20a3416b5..e73bbd5c9bb 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java @@ -1,7 +1,6 @@ // 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. - // Code generated by protocol buffer compiler. Do not edit! package org.wpilib.commands3.proto; @@ -18,14 +17,14 @@ import us.hebi.quickbuf.ProtoUtil; import us.hebi.quickbuf.RepeatedMessage; -/** Protobuf type {@code ProtobufScheduler} */ +/** + * Protobuf type {@code ProtobufScheduler} + */ @SuppressWarnings("hiding") public final class ProtobufScheduler extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; /** - * - * *
    *  How much time the scheduler took in its last `run()` invocation.
    * 
@@ -35,8 +34,6 @@ public final class ProtobufScheduler extends ProtoMessage imp private double lastTimeMs; /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
@@ -45,14 +42,15 @@ public final class ProtobufScheduler extends ProtoMessage imp
    *
    * repeated .wpi.proto.ProtobufCommand queued_commands = 1;
    */
-  private final RepeatedMessage queuedCommands =
-      RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory());
+  private final RepeatedMessage queuedCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory());
 
-  /** repeated .wpi.proto.ProtobufCommand running_commands = 2; */
-  private final RepeatedMessage runningCommands =
-      RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory());
+  /**
+   * repeated .wpi.proto.ProtobufCommand running_commands = 2;
+   */
+  private final RepeatedMessage runningCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory());
 
-  private ProtobufScheduler() {}
+  private ProtobufScheduler() {
+  }
 
   /**
    * @return a new empty instance of {@code ProtobufScheduler}
@@ -62,14 +60,11 @@ public static ProtobufScheduler newInstance() {
   }
 
   /**
-   *
-   *
    * 
    *  How much time the scheduler took in its last `run()` invocation.
    * 
* * optional double last_time_ms = 3; - * * @return whether the lastTimeMs field is set */ public boolean hasLastTimeMs() { @@ -77,14 +72,11 @@ public boolean hasLastTimeMs() { } /** - * - * *
    *  How much time the scheduler took in its last `run()` invocation.
    * 
* * optional double last_time_ms = 3; - * * @return this */ public ProtobufScheduler clearLastTimeMs() { @@ -94,14 +86,11 @@ public ProtobufScheduler clearLastTimeMs() { } /** - * - * *
    *  How much time the scheduler took in its last `run()` invocation.
    * 
* * optional double last_time_ms = 3; - * * @return the lastTimeMs */ public double getLastTimeMs() { @@ -109,14 +98,11 @@ public double getLastTimeMs() { } /** - * - * *
    *  How much time the scheduler took in its last `run()` invocation.
    * 
* * optional double last_time_ms = 3; - * * @param value the lastTimeMs to set * @return this */ @@ -127,8 +113,6 @@ public ProtobufScheduler setLastTimeMs(final double value) { } /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
@@ -136,7 +120,6 @@ public ProtobufScheduler setLastTimeMs(final double value) {
    * 
* * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * * @return whether the queuedCommands field is set */ public boolean hasQueuedCommands() { @@ -144,8 +127,6 @@ public boolean hasQueuedCommands() { } /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
@@ -153,7 +134,6 @@ public boolean hasQueuedCommands() {
    * 
* * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * * @return this */ public ProtobufScheduler clearQueuedCommands() { @@ -163,19 +143,18 @@ public ProtobufScheduler clearQueuedCommands() { } /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
    *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    * 
* - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; This method returns the - * internal storage object without modifying any has state. The returned object should not be - * modified and be treated as read-only. + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. * - *

Use {@link #getMutableQueuedCommands()} if you want to modify it. + * Use {@link #getMutableQueuedCommands()} if you want to modify it. * * @return internal storage object for reading */ @@ -184,17 +163,17 @@ public RepeatedMessage getQueuedCommands() { } /** - * - * *

    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
    *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    * 
* - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; This method returns the - * internal storage object and sets the corresponding has state. The returned object will become - * part of this message and its contents may be modified as long as the has state is not cleared. + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. * * @return internal storage object for modifications */ @@ -204,8 +183,6 @@ public RepeatedMessage getMutableQueuedCommands() { } /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
@@ -213,7 +190,6 @@ public RepeatedMessage getMutableQueuedCommands() {
    * 
* * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * * @param value the queuedCommands to add * @return this */ @@ -224,8 +200,6 @@ public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { } /** - * - * *
    *  Note: commands are generally queued by triggers, which occurs immediately before they are
    *  promoted and start running. Entries will only appear here when serializing a scheduler
@@ -233,7 +207,6 @@ public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) {
    * 
* * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * * @param values the queuedCommands to add * @return this */ @@ -245,7 +218,6 @@ public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { /** * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * * @return whether the runningCommands field is set */ public boolean hasRunningCommands() { @@ -254,7 +226,6 @@ public boolean hasRunningCommands() { /** * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * * @return this */ public ProtobufScheduler clearRunningCommands() { @@ -264,11 +235,12 @@ public ProtobufScheduler clearRunningCommands() { } /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; This method returns the - * internal storage object without modifying any has state. The returned object should not be - * modified and be treated as read-only. + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. * - *

Use {@link #getMutableRunningCommands()} if you want to modify it. + * Use {@link #getMutableRunningCommands()} if you want to modify it. * * @return internal storage object for reading */ @@ -277,9 +249,11 @@ public RepeatedMessage getRunningCommands() { } /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; This method returns the - * internal storage object and sets the corresponding has state. The returned object will become - * part of this message and its contents may be modified as long as the has state is not cleared. + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. * * @return internal storage object for modifications */ @@ -290,7 +264,6 @@ public RepeatedMessage getMutableRunningCommands() { /** * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * * @param value the runningCommands to add * @return this */ @@ -302,7 +275,6 @@ public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { /** * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * * @param values the runningCommands to add * @return this */ @@ -377,9 +349,9 @@ public boolean equals(Object o) { } ProtobufScheduler other = (ProtobufScheduler) o; return bitField0_ == other.bitField0_ - && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) - && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) - && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) + && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) + && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); } @Override @@ -409,13 +381,10 @@ protected int computeSerializedSize() { size += 9; } if ((bitField0_ & 0x00000002) != 0) { - size += - (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); + size += (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); } if ((bitField0_ & 0x00000004) != 0) { - size += - (1 * runningCommands.length()) - + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); + size += (1 * runningCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); } return size; } @@ -427,46 +396,41 @@ public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { int tag = input.readTag(); while (true) { switch (tag) { - case 25: - { - // lastTimeMs - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 10) { - break; - } + case 25: { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 10) { + break; } - case 10: - { - // queuedCommands - tag = input.readRepeatedMessage(queuedCommands, tag); - bitField0_ |= 0x00000002; - if (tag != 18) { - break; - } + } + case 10: { + // queuedCommands + tag = input.readRepeatedMessage(queuedCommands, tag); + bitField0_ |= 0x00000002; + if (tag != 18) { + break; } - case 18: - { - // runningCommands - tag = input.readRepeatedMessage(runningCommands, tag); - bitField0_ |= 0x00000004; - if (tag != 0) { - break; - } + } + case 18: { + // runningCommands + tag = input.readRepeatedMessage(runningCommands, tag); + bitField0_ |= 0x00000004; + if (tag != 0) { + break; } - case 0: - { + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { return this; } - default: - { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } + tag = input.readTag(); + break; + } } } } @@ -494,49 +458,45 @@ public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { while (!input.isAtEnd()) { switch (input.readFieldHash()) { case 1958056841: - case -740797521: - { - if (input.isAtField(FieldNames.lastTimeMs)) { - if (!input.trySkipNullValue()) { - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); + case -740797521: { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; } - break; + } else { + input.skipUnknownField(); } + break; + } case -167160549: - case -1904270380: - { - if (input.isAtField(FieldNames.queuedCommands)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(queuedCommands); - bitField0_ |= 0x00000002; - } - } else { - input.skipUnknownField(); + case -1904270380: { + if (input.isAtField(FieldNames.queuedCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(queuedCommands); + bitField0_ |= 0x00000002; } - break; + } else { + input.skipUnknownField(); } + break; + } case -1719052953: - case 1526672648: - { - if (input.isAtField(FieldNames.runningCommands)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(runningCommands); - bitField0_ |= 0x00000004; - } - } else { - input.skipUnknownField(); + case 1526672648: { + if (input.isAtField(FieldNames.runningCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(runningCommands); + bitField0_ |= 0x00000004; } - break; - } - default: - { + } else { input.skipUnknownField(); - break; } + break; + } + default: { + input.skipUnknownField(); + break; + } } } input.endObject(); @@ -553,8 +513,8 @@ public boolean isEmpty() { return ((bitField0_) == 0); } - public static ProtobufScheduler parseFrom(final byte[] data) - throws InvalidProtocolBufferException { + public static ProtobufScheduler parseFrom(final byte[] data) throws + InvalidProtocolBufferException { return ProtoMessage.mergeFrom(new ProtobufScheduler(), data).checkInitialized(); } @@ -589,13 +549,14 @@ public ProtobufScheduler create() { } } - /** Contains name constants used for serializing JSON */ + /** + * Contains name constants used for serializing JSON + */ static class FieldNames { static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); static final FieldName queuedCommands = FieldName.forField("queuedCommands", "queued_commands"); - static final FieldName runningCommands = - FieldName.forField("runningCommands", "running_commands"); + static final FieldName runningCommands = FieldName.forField("runningCommands", "running_commands"); } } diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java index 9a5abd7bc82..613232c0ae5 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java @@ -1,7 +1,6 @@ // 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. - // Code generated by protocol buffer compiler. Do not edit! package org.wpilib.commands3.proto; @@ -10,66 +9,57 @@ import us.hebi.quickbuf.RepeatedByte; public final class Scheduler { - private static final RepeatedByte descriptorData = - ProtoUtil.decodeBase64( - 2511, - "Ciljb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5wcm90bxIJd3BpLnByb3RvIjEKG1By" - + "b3RvYnVmUmVxdWlyZWFibGVSZXNvdXJjZRISCgRuYW1lGAEgASgJUgRuYW1lIsACCg9Qcm90b2J1ZkNv" - + "bW1hbmQSDgoCaWQYASABKA1SAmlkEiAKCXBhcmVudF9pZBgCIAEoDUgAUghwYXJlbnRJZIgBARISCgRu" - + "YW1lGAMgASgJUgRuYW1lEhoKCHByaW9yaXR5GAQgASgFUghwcmlvcml0eRJKCgxyZXF1aXJlbWVudHMY" - + "BSADKAsyJi53cGkucHJvdG8uUHJvdG9idWZSZXF1aXJlYWJsZVJlc291cmNlUgxyZXF1aXJlbWVudHMS" - + "JQoMbGFzdF90aW1lX21zGAYgASgBSAFSCmxhc3RUaW1lTXOIAQESJwoNdG90YWxfdGltZV9tcxgHIAEo" - + "AUgCUgt0b3RhbFRpbWVNc4gBAUIMCgpfcGFyZW50X2lkQg8KDV9sYXN0X3RpbWVfbXNCEAoOX3RvdGFs" - + "X3RpbWVfbXMiwQEKEVByb3RvYnVmU2NoZWR1bGVyEkMKD3F1ZXVlZF9jb21tYW5kcxgBIAMoCzIaLndw" - + "aS5wcm90by5Qcm90b2J1ZkNvbW1hbmRSDnF1ZXVlZENvbW1hbmRzEkUKEHJ1bm5pbmdfY29tbWFuZHMY" - + "AiADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg9ydW5uaW5nQ29tbWFuZHMSIAoMbGFzdF90" - + "aW1lX21zGAMgASgBUgpsYXN0VGltZU1zQh4KGm9yZy53cGlsaWIuY29tbWFuZHMzLnByb3RvUAFKtA4K" - + "BhIEAAA1AQoICgEMEgMAABIKCAoBAhIDAgASCggKAQgSAwQAMwoJCgIIARIDBAAzCggKAQgSAwUAIgoJ" - + "CgIIChIDBQAiCpUBCgIEABIEDQAPATKIAQphbGx3cGlsaWIgJCBwcm90b2MtcXVpY2tidWYgXAotLXF1" - + "aWNrYnVmX291dD1nZW5fZGVzY3JpcHRvcnM9dHJ1ZTpjb21tYW5kc3YzL3NyYy9tYWluL2phdmEgXApj" - + "b21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5wcm90bwoKCgoDBAABEgMNCCMKCwoEBAAC" - + "ABIDDgISCgwKBQQAAgAFEgMOAggKDAoFBAACAAESAw4JDQoMCgUEAAIAAxIDDhARCgoKAgQBEgQRACoB" - + "CgoKAwQBARIDEQgXCnEKBAQBAgASAxQCEBpkIEEgdW5pcXVlIElEIGZvciB0aGUgY29tbWFuZC4KIERp" - + "ZmZlcmVudCBpbnZvY2F0aW9ucyBvZiB0aGUgc2FtZSBjb21tYW5kIG9iamVjdCBoYXZlIGRpZmZlcmVu" - + "dCBJRHMuCgoMCgUEAQIABRIDFAIICgwKBQQBAgABEgMUCQsKDAoFBAECAAMSAxQODwphCgQEAQIBEgMY" - + "AiAaVCBUaGUgSUQgb2YgdGhlIHBhcmVudCBjb21tYW5kLgogTm90IGluY2x1ZGVkIGluIHRoZSBtZXNz", - "YWdlIGZvciB0b3AtbGV2ZWwgY29tbWFuZHMuCgoMCgUEAQIBBBIDGAIKCgwKBQQBAgEFEgMYCxEKDAoF" - + "BAECAQESAxgSGwoMCgUEAQIBAxIDGB4fCicKBAQBAgISAxsCEhoaIFRoZSBuYW1lIG9mIHRoZSBjb21t" - + "YW5kLgoKDAoFBAECAgUSAxsCCAoMCgUEAQICARIDGwkNCgwKBQQBAgIDEgMbEBEKMQoEBAECAxIDHgIV" - + "GiQgVGhlIHByaW9yaXR5IGxldmVsIG9mIHRoZSBjb21tYW5kLgoKDAoFBAECAwUSAx4CBwoMCgUEAQID" - + "ARIDHggQCgwKBQQBAgMDEgMeExQKNQoEBAECBBIDIQI4GiggVGhlIHJlc291cmNlcyByZXF1aXJlZCBi" - + "eSB0aGUgY29tbWFuZC4KCgwKBQQBAgQEEgMhAgoKDAoFBAECBAYSAyELJgoMCgUEAQIEARIDISczCgwK" - + "BQQBAgQDEgMhNjcKjgEKBAQBAgUSAyUCIxqAASBIb3cgbXVjaCB0aW1lIHRoZSBjb21tYW5kIHRvb2sg" - + "dG8gZXhlY3V0ZSBpbiBpdHMgbW9zdCByZWNlbnQgcnVuLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3Nh" - + "Z2UgZm9yIGFuIGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgUEEgMlAgoKDAoFBAECBQUS" - + "AyULEQoMCgUEAQIFARIDJRIeCgwKBQQBAgUDEgMlISIKgAEKBAQBAgYSAykCJBpzIEhvdyBsb25nIHRo" - + "ZSBjb21tYW5kIGhhcyB0YWtlbiB0byBydW4sIGluIGFnZ3JlZ2F0ZS4KIE9ubHkgaW5jbHVkZWQgaW4g" - + "YSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQuCgoMCgUEAQIGBBIDKQIKCgwK" - + "BQQBAgYFEgMpCxEKDAoFBAECBgESAykSHwoMCgUEAQIGAxIDKSIjCgoKAgQCEgQsADUBCgoKAwQCARID" - + "LAgZCo0CCgQEAgIAEgMwAi8a/wEgTm90ZTogY29tbWFuZHMgYXJlIGdlbmVyYWxseSBxdWV1ZWQgYnkg" - + "dHJpZ2dlcnMsIHdoaWNoIG9jY3VycyBpbW1lZGlhdGVseSBiZWZvcmUgdGhleSBhcmUKIHByb21vdGVk" - + "IGFuZCBzdGFydCBydW5uaW5nLiBFbnRyaWVzIHdpbGwgb25seSBhcHBlYXIgaGVyZSB3aGVuIHNlcmlh" - + "bGl6aW5nIGEgc2NoZWR1bGVyCiBfYWZ0ZXJfIG1hbnVhbGx5IHNjaGVkdWxpbmcgYSBjb21tYW5kIGJ1" - + "dCBfYmVmb3JlXyBjYWxsaW5nIHNjaGVkdWxlci5ydW4oKQoKDAoFBAICAAQSAzACCgoMCgUEAgIABhID" - + "MAsaCgwKBQQCAgABEgMwGyoKDAoFBAICAAMSAzAtLgoLCgQEAgIBEgMxAjAKDAoFBAICAQQSAzECCgoM" - + "CgUEAgIBBhIDMQsaCgwKBQQCAgEBEgMxGysKDAoFBAICAQMSAzEuLwpPCgQEAgICEgM0AhoaQiBIb3cg", - "bXVjaCB0aW1lIHRoZSBzY2hlZHVsZXIgdG9vayBpbiBpdHMgbGFzdCBgcnVuKClgIGludm9jYXRpb24u" - + "CgoMCgUEAgICBRIDNAIICgwKBQQCAgIBEgM0CRUKDAoFBAICAgMSAzQYGWIGcHJvdG8z"); + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2495, + "Cg9zY2hlZHVsZXIucHJvdG8SCXdwaS5wcm90byIxChtQcm90b2J1ZlJlcXVpcmVhYmxlUmVzb3VyY2US" + + "EgoEbmFtZRgBIAEoCVIEbmFtZSLAAgoPUHJvdG9idWZDb21tYW5kEg4KAmlkGAEgASgNUgJpZBIgCglw" + + "YXJlbnRfaWQYAiABKA1IAFIIcGFyZW50SWSIAQESEgoEbmFtZRgDIAEoCVIEbmFtZRIaCghwcmlvcml0" + + "eRgEIAEoBVIIcHJpb3JpdHkSSgoMcmVxdWlyZW1lbnRzGAUgAygLMiYud3BpLnByb3RvLlByb3RvYnVm" + + "UmVxdWlyZWFibGVSZXNvdXJjZVIMcmVxdWlyZW1lbnRzEiUKDGxhc3RfdGltZV9tcxgGIAEoAUgBUgps" + + "YXN0VGltZU1ziAEBEicKDXRvdGFsX3RpbWVfbXMYByABKAFIAlILdG90YWxUaW1lTXOIAQFCDAoKX3Bh" + + "cmVudF9pZEIPCg1fbGFzdF90aW1lX21zQhAKDl90b3RhbF90aW1lX21zIsEBChFQcm90b2J1ZlNjaGVk" + + "dWxlchJDCg9xdWV1ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg5x" + + "dWV1ZWRDb21tYW5kcxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnByb3RvLlByb3RvYnVm" + + "Q29tbWFuZFIPcnVubmluZ0NvbW1hbmRzEiAKDGxhc3RfdGltZV9tcxgDIAEoAVIKbGFzdFRpbWVNc0Ie" + + "Chpvcmcud3BpbGliLmNvbW1hbmRzMy5wcm90b1ABSr4OCgYSBAAANQEKCAoBDBIDAAASCggKAQISAwIA" + + "EgoICgEIEgMEADMKCQoCCAESAwQAMwoICgEIEgMFACIKCQoCCAoSAwUAIgqfAQoCBAASBA0ADwEykgEK" + + "YWxsd3BpbGliICQgcHJvdG9jLXF1aWNrYnVmIFwKLS1xdWlja2J1Zl9vdXQ9Z2VuX2Rlc2NyaXB0b3Jz" + + "PXRydWU6Y29tbWFuZHN2My9zcmMvZ2VuZXJhdGVkL21haW4vamF2YSBcCmNvbW1hbmRzdjMvc3JjL21h" + + "aW4vcHJvdG8vc2NoZWR1bGVyLnByb3RvCgoKCgMEAAESAw0IIwoLCgQEAAIAEgMOAhIKDAoFBAACAAUS" + + "Aw4CCAoMCgUEAAIAARIDDgkNCgwKBQQAAgADEgMOEBEKCgoCBAESBBEAKgEKCgoDBAEBEgMRCBcKcQoE" + + "BAECABIDFAIQGmQgQSB1bmlxdWUgSUQgZm9yIHRoZSBjb21tYW5kLgogRGlmZmVyZW50IGludm9jYXRp" + + "b25zIG9mIHRoZSBzYW1lIGNvbW1hbmQgb2JqZWN0IGhhdmUgZGlmZmVyZW50IElEcy4KCgwKBQQBAgAF" + + "EgMUAggKDAoFBAECAAESAxQJCwoMCgUEAQIAAxIDFA4PCmEKBAQBAgESAxgCIBpUIFRoZSBJRCBvZiB0" + + "aGUgcGFyZW50IGNvbW1hbmQuCiBOb3QgaW5jbHVkZWQgaW4gdGhlIG1lc3NhZ2UgZm9yIHRvcC1sZXZl", + "bCBjb21tYW5kcy4KCgwKBQQBAgEEEgMYAgoKDAoFBAECAQUSAxgLEQoMCgUEAQIBARIDGBIbCgwKBQQB" + + "AgEDEgMYHh8KJwoEBAECAhIDGwISGhogVGhlIG5hbWUgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQICBRID" + + "GwIICgwKBQQBAgIBEgMbCQ0KDAoFBAECAgMSAxsQEQoxCgQEAQIDEgMeAhUaJCBUaGUgcHJpb3JpdHkg" + + "bGV2ZWwgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQIDBRIDHgIHCgwKBQQBAgMBEgMeCBAKDAoFBAECAwMS" + + "Ax4TFAo1CgQEAQIEEgMhAjgaKCBUaGUgcmVzb3VyY2VzIHJlcXVpcmVkIGJ5IHRoZSBjb21tYW5kLgoK" + + "DAoFBAECBAQSAyECCgoMCgUEAQIEBhIDIQsmCgwKBQQBAgQBEgMhJzMKDAoFBAECBAMSAyE2NwqOAQoE" + + "BAECBRIDJQIjGoABIEhvdyBtdWNoIHRpbWUgdGhlIGNvbW1hbmQgdG9vayB0byBleGVjdXRlIGluIGl0" + + "cyBtb3N0IHJlY2VudCBydW4uCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZl" + + "bHkgcnVubmluZyBjb21tYW5kLgoKDAoFBAECBQQSAyUCCgoMCgUEAQIFBRIDJQsRCgwKBQQBAgUBEgMl" + + "Eh4KDAoFBAECBQMSAyUhIgqAAQoEBAECBhIDKQIkGnMgSG93IGxvbmcgdGhlIGNvbW1hbmQgaGFzIHRh" + + "a2VuIHRvIHJ1biwgaW4gYWdncmVnYXRlLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFu" + + "IGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgYEEgMpAgoKDAoFBAECBgUSAykLEQoMCgUE" + + "AQIGARIDKRIfCgwKBQQBAgYDEgMpIiMKCgoCBAISBCwANQEKCgoDBAIBEgMsCBkKjQIKBAQCAgASAzAC" + + "Lxr/ASBOb3RlOiBjb21tYW5kcyBhcmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2gg" + + "b2NjdXJzIGltbWVkaWF0ZWx5IGJlZm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5p" + + "bmcuIEVudHJpZXMgd2lsbCBvbmx5IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVs" + + "ZXIKIF9hZnRlcl8gbWFudWFsbHkgc2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxp" + + "bmcgc2NoZWR1bGVyLnJ1bigpCgoMCgUEAgIABBIDMAIKCgwKBQQCAgAGEgMwCxoKDAoFBAICAAESAzAb" + + "KgoMCgUEAgIAAxIDMC0uCgsKBAQCAgESAzECMAoMCgUEAgIBBBIDMQIKCgwKBQQCAgEGEgMxCxoKDAoF" + + "BAICAQESAzEbKwoMCgUEAgIBAxIDMS4vCk8KBAQCAgISAzQCGhpCIEhvdyBtdWNoIHRpbWUgdGhlIHNj", + "aGVkdWxlciB0b29rIGluIGl0cyBsYXN0IGBydW4oKWAgaW52b2NhdGlvbi4KCgwKBQQCAgIFEgM0AggK" + + "DAoFBAICAgESAzQJFQoMCgUEAgICAxIDNBgZYgZwcm90bzM="); - static final Descriptors.FileDescriptor descriptor = - Descriptors.FileDescriptor.internalBuildGeneratedFileFrom( - "commandsv3/src/main/proto/scheduler.proto", "wpi.proto", descriptorData); + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("scheduler.proto", "wpi.proto", descriptorData); - static final Descriptors.Descriptor wpi_proto_ProtobufRequireableResource_descriptor = - descriptor.internalContainedType( - 56, 49, "ProtobufRequireableResource", "wpi.proto.ProtobufRequireableResource"); + static final Descriptors.Descriptor wpi_proto_ProtobufRequireableResource_descriptor = descriptor.internalContainedType(30, 49, "ProtobufRequireableResource", "wpi.proto.ProtobufRequireableResource"); - static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = - descriptor.internalContainedType(108, 320, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(82, 320, "ProtobufCommand", "wpi.proto.ProtobufCommand"); - static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = - descriptor.internalContainedType( - 431, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(405, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); /** * @return this proto file's descriptor. From 8127e61fa2d0c72e52af769e6d6dd0bd12420e83 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 22:33:02 -0400 Subject: [PATCH 068/153] Replace snippet tags with code blocks google-java-format doesn't know how to handle snippet blocks and breaks the formatting check --- .../java/org/wpilib/commands3/Command.java | 82 +++++++++---------- .../java/org/wpilib/commands3/Coroutine.java | 8 +- 2 files changed, 45 insertions(+), 45 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index a3fdabbab46..faa9dddd04c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -21,51 +21,51 @@ * command implementation must call {@link Coroutine#yield()} within any periodic * loop. Failure to do so may result in an unrecoverable infinite loop. * - *

{@snippet lang="java": - * // A 2013-style class-based command definition - * class ClassBasedCommand extends Command { - * public ClassBasedCommand(Subsystem requiredSubsystem) { - * addRequirements(requiredSubsystem); - * } + *

{@code
+ * // A 2013-style class-based command definition
+ * class ClassBasedCommand extends Command {
+ *   public ClassBasedCommand(Subsystem requiredSubsystem) {
+ *     addRequirements(requiredSubsystem);
+ *   }
  *
- *       @Override
- *       public void initialize() {}
+ *   @Override
+ *   public void initialize() {}
  *
- *       @Override
- *       public void execute() {}
+ *   @Override
+ *   public void execute() {}
  *
- *       @Override
- *       public void end(boolean interrupted) {}
+ *   @Override
+ *   public void end(boolean interrupted) {}
  *
- *       @Override
- *       public void isFinished() { return true; }
+ *   @Override
+ *   public void isFinished() { return true; }
  *
- *       @Override
- *       public String getName() { return "The Command"; }
- *     }
+ *   @Override
+ *   public String getName() { return "The Command"; }
+ * }
  *
- *     Command command = new ClassBasedCommand(requiredSubsystem);
+ * Command command = new ClassBasedCommand(requiredSubsystem);
  *
- *     // Or a 2020-style function-based command
- *     Command command = requiredSubsystem
- *       .runOnce(() -> initialize())
- *       .andThen(
- *         requiredSubsystem
- *           .run(() -> execute())
- *           .until(() -> isFinished())
- *           .onFinish(() -> end())
- *       ).withName("The Command");
+ * // Or a 2020-style function-based command
+ * Command command = requiredSubsystem
+ *   .runOnce(() -> initialize())
+ *   .andThen(
+ *     requiredSubsystem
+ *       .run(() -> execute())
+ *       .until(() -> isFinished())
+ *       .onFinish(() -> end())
+ *   ).withName("The Command");
  *
- *     // Can be represented with a 2025-style async-based definition
- *     Command command = requiredSubsystem.run(coroutine -> {
- *       initialize();
- *       while (!isFinished()) {
- *         coroutine.yield();
- *         execute();
- *       }
- *       end();
- *     }).named("The Command");
- *     }
+ * // Can be represented with a 2027-style async-based definition
+ * Command command = requiredSubsystem.run(coroutine -> {
+ *   initialize();
+ *   while (!isFinished()) {
+ *     coroutine.yield();
+ *     execute();
+ *   }
+ *   end();
+ * }).named("The Command");
+ * }
*/ public interface Command { /** The default command priority. */ @@ -267,13 +267,13 @@ default ParallelGroupBuilder until(BooleanSupplier endCondition) { * Starts creating a command sequence, starting from this command and then running the next one. * More commands can be added with the builder before naming and creating the sequence. * - *

{@snippet lang="java": + *

{@code
    * Sequence aThenBThenC =
    *   commandA()
    *     .andThen(commandB())
    *     .andThen(commandC())
    *     .withAutomaticName();
-   * }
+   * }
* * @param next The command to run after this one in the sequence * @return A sequence builder @@ -286,12 +286,12 @@ default SequenceBuilder andThen(Command next) { * Starts creating a parallel command group, running this command alongside one or more other * commands. The group will exit once every command has finished. * - *

{@snippet lang="java": + *

{@code
    * ParallelGroup abc =
    *   commandA()
    *     .alongWith(commandB(), commandC())
    *     .withAutomaticName();
-   * }
+   * }
* * @param parallel The commands to run in parallel with this one * @return A parallel group builder diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 0d088390fdf..0623a20c6a8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -78,7 +78,7 @@ public void park() { * parent command cancels it. The parent command will continue executing while the forked command * runs, and can resync with the forked command using {@link #await(Command)}. * - *

{@snippet lang="java": + *

{@code
    * Command example() {
    *   return Command.noRequirements(coroutine -> {
    *     Command inner = ...;
@@ -88,7 +88,7 @@ public void park() {
    *     coroutine.await(inner);
    *   }).named("Example");
    * }
-   * }
+   * }
* * @param commands The commands to fork. */ @@ -236,7 +236,7 @@ private static void validateNoConflicts(Collection commands) { * *

For example, a basic autonomous routine that drives straight for 5 seconds: * - *

{@snippet lang="java": + *

{@code
    * Command timedDrive() {
    *   return drivebase.run(coroutine -> {
    *     drivebase.tankDrive(1, 1);
@@ -244,7 +244,7 @@ private static void validateNoConflicts(Collection commands) {
    *     drivebase.stop();
    *   }).named("Timed Drive");
    * }
-   * }
+   * }
* * @param duration the duration of time to wait */ From 33a28d9d72bc216fdb57df451ad6f63d6132bf7c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 30 Jul 2025 22:44:19 -0400 Subject: [PATCH 069/153] Stop wpiformat from running against generated files --- commandsv3/.styleguide | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 commandsv3/.styleguide diff --git a/commandsv3/.styleguide b/commandsv3/.styleguide new file mode 100644 index 00000000000..0f2122eeb7e --- /dev/null +++ b/commandsv3/.styleguide @@ -0,0 +1,12 @@ +modifiableFileExclude { + \.patch$ +} + +generatedFileExclude { + src/generated/main/java/org/wpilib/commands3/button/ + src/generated/main/java/org/wpilib/commands3/proto/ +} + +repoRootNameOverride { + commandsv3 +} From d188948399454e14779966ce7db22dbe4bbf57ec Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 19:15:12 -0400 Subject: [PATCH 070/153] Minor cleanup for readability `schedule()` is already a no-op if given a command that's already scheduled or running, so wrapping in a check is redundant and harms readability --- .../java/org/wpilib/commands3/Coroutine.java | 21 ++++++++++--------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 0623a20c6a8..9c7d1bf2689 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -7,6 +7,7 @@ import edu.wpi.first.units.measure.Time; import java.util.Arrays; import java.util.Collection; +import java.util.List; import java.util.function.BooleanSupplier; import java.util.function.Consumer; import java.util.stream.Collectors; @@ -90,11 +91,17 @@ public void park() { * } * }
* + *

Note: forking a command that conflicts with a higher-priority command will fail. The forked + * command will not be scheduled, and the existing command will continue to run.

+ * * @param commands The commands to fork. */ public void fork(Command... commands) { requireMounted(); + // Check for user error; there's no reason to fork conflicting commands simultaneously + validateNoConflicts(List.of(commands)); + // Shorthand; this is handy for user-defined compositions for (var command : commands) { m_scheduler.schedule(command); @@ -112,9 +119,7 @@ public void fork(Command... commands) { public void await(Command command) { requireMounted(); - if (!m_scheduler.isScheduledOrRunning(command)) { - m_scheduler.schedule(command); - } + m_scheduler.schedule(command); while (m_scheduler.isScheduledOrRunning(command)) { // If the command is a one-shot, then the schedule call will completely execute the command. @@ -135,11 +140,8 @@ public void awaitAll(Collection commands) { validateNoConflicts(commands); - // Schedule anything that's not already queued or running for (var command : commands) { - if (!m_scheduler.isScheduledOrRunning(command)) { - m_scheduler.schedule(command); - } + m_scheduler.schedule(command); } while (commands.stream().anyMatch(m_scheduler::isScheduledOrRunning)) { @@ -174,15 +176,14 @@ public void awaitAny(Collection commands) { // Schedule anything that's not already queued or running for (var command : commands) { - if (!m_scheduler.isScheduledOrRunning(command)) { - m_scheduler.schedule(command); - } + m_scheduler.schedule(command); } while (commands.stream().allMatch(m_scheduler::isScheduledOrRunning)) { this.yield(); } + // At least one command exited; cancel the rest. commands.forEach(m_scheduler::cancel); } From 56a0798cb9c65f7467278f3c77935eb49d4de260 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 19:18:59 -0400 Subject: [PATCH 071/153] Fix nested commands being allowed to interrupt higher-priority commands The `isSchedulable()` check would always return true for nested commands. This caused them to be able to interrupt higher priority commands Fix the check by only skipping conflict checks for direct ancestor commands --- .../java/org/wpilib/commands3/Scheduler.java | 27 +++++++++---- .../org/wpilib/commands3/SchedulerTest.java | 39 +++++++++++++++++++ 2 files changed, 59 insertions(+), 7 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index f4293e1dca8..3e9672e58c5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -15,6 +15,7 @@ import java.util.ArrayList; import java.util.Collection; import java.util.Collections; +import java.util.HashSet; import java.util.Iterator; import java.util.LinkedHashMap; import java.util.LinkedHashSet; @@ -239,17 +240,29 @@ ScheduleResult schedule(Binding binding) { return ScheduleResult.SUCCESS; } + /** + * Checks if a command can be scheduled. Requirements are that the command either does not + * conflict with any running commands, or is at least the same priority as every running command + * with which it conflicts. If a parent command is attempting to schedule a child, the child will + * never be considered to be conflicting with the parent or any ancestors. + * + * @param command The command to check + * @return True if the command meets all scheduling requirements, false if not + */ private boolean isSchedulable(Command command) { - if (currentState() != null) { - // Bypass scheduling check if being scheduled as a nested command. - // The schedule() method will throw an error when attempting to schedule a nested command - // that requires a resource that the parent doesn't - return true; + Set ancestors = new HashSet<>(); + for (var state = currentState(); state != null; state = m_commandStates.get(state.parent())) { + ancestors.add(state); } - // Scheduling from outside a command, eg a trigger binding or manual schedule call // Check for conflicts with the commands that are already running - for (Command c : m_commandStates.keySet()) { + for (var state : m_commandStates.values()) { + if (ancestors.contains(state)) { + // Can't conflict with an ancestor command + continue; + } + + var c = state.command(); if (c.conflictsWith(command) && command.isLowerPriorityThan(c)) { return false; } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 79c87ce5f4a..41e27a14377 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -459,6 +459,7 @@ void compositionsDoNotCancelParent() { m_scheduler.schedule(group); m_scheduler.run(); + // second child interrupts first child assertEquals( List.of("Group", "Second Child"), m_scheduler.getRunningCommands().stream().map(Command::name).toList()); @@ -824,6 +825,44 @@ void nestedOneShotCompositionsAllRunInOneCycle() { assertFalse(m_scheduler.isRunning(command), "Command should have exited after one cycle"); } + @Test + void childConflictsWithHigherPriorityTopLevel() { + var resource = new RequireableResource("Resource", m_scheduler); + var top = resource.run(Coroutine::park).withPriority(10).named("Top"); + + // Child conflicts with and is lower priority than the Top command + // It should not be scheduled, and the parent command should exit immediately + var child = resource.run(Coroutine::park).named("Child"); + var parent = Command.noRequirements(co -> co.await(child)).named("Parent"); + + m_scheduler.schedule(top); + m_scheduler.schedule(parent); + m_scheduler.run(); + + assertTrue(m_scheduler.isRunning(top), "Top command should not have been interrupted"); + assertFalse(m_scheduler.isRunning(child), "Conflicting child should not have run"); + assertFalse(m_scheduler.isRunning(parent), "Parent of conflicting child should have exited"); + } + + @Test + void childConflictsWithLowerPriorityTopLevel() { + var resource = new RequireableResource("Resource", m_scheduler); + var top = resource.run(Coroutine::park).withPriority(-10).named("Top"); + + // Child conflicts with and is lower priority than the Top command + // It should not be scheduled, and the parent command should exit immediately + var child = resource.run(Coroutine::park).named("Child"); + var parent = Command.noRequirements(co -> co.await(child)).named("Parent"); + + m_scheduler.schedule(top); + m_scheduler.schedule(parent); + m_scheduler.run(); + + assertFalse(m_scheduler.isRunning(top), "Top command should have been interrupted"); + assertTrue(m_scheduler.isRunning(child), "Conflicting child should be running"); + assertTrue(m_scheduler.isRunning(parent), "Parent of conflicting child should be running"); + } + record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { @Override public void run(Coroutine coroutine) { From f292977e56b0b1c4648f5266db0e2dfd09b2b9e4 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 19:20:11 -0400 Subject: [PATCH 072/153] Improve top-level documentation for Scheduler and Continuation Include warnings for using them in multithreaded contexts --- .../org/wpilib/commands3/Continuation.java | 19 ++++- .../java/org/wpilib/commands3/Scheduler.java | 74 ++++++++++++++++++- 2 files changed, 89 insertions(+), 4 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 7445a924897..f9bc699b085 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -9,7 +9,24 @@ import java.lang.invoke.MethodType; import java.lang.invoke.WrongMethodTypeException; -/** A wrapper around the JDK internal Continuation class. */ +/** + * A wrapper around the JDK internal Continuation class. Continuations are one-shot (i.e., not + * reusable after completion) and allow stack frames to be paused and resumed at a later time. They + * are the underpinning for {@link VirtualThread virtual threads}, which have their own scheduler + * and JVM support. Bare continuations are designed for internal use by the JVM; we have forcibly + * opened access to them for use by the commands framework due to limitations of virtual threads; + * notably, their complete lack of determinism and timing, which are critically important for + * real-time systems like robots. + * + *

ONLY USE CONTINUATIONS IN A SINGLE THREADED CONTEXT. The JVM and JIT + * compilers make fundamental assumptions about how continuations are used, and rely on the code + * that uses it (which was intended to be virtual threads) to use it safely. Failure to use + * this API safely can result in JIT compilers to issue invalid code causing buggy behavior and JVM + * crashes at any time, up to and including on a field during an official match. + * + *

Teams don't need to use continuations directly with the commands framework; all mounting and + * unmounting is handled by the command scheduler and a coroutine wrapper. + */ public final class Continuation { // The underlying jdk.internal.vm.Continuation object final Object m_continuation; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 3e9672e58c5..a9efa97c7f5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -27,7 +27,69 @@ import java.util.stream.Collectors; import org.wpilib.commands3.proto.SchedulerProto; -/** Manages the lifecycles of {@link Coroutine}-based {@link Command Commands}. */ +/** + * Manages the lifecycles of {@link Coroutine}-based {@link Command Commands}. Commands may be + * scheduled directly using {@link #schedule(Command)}, or be bound to {@link Trigger Triggers} to + * automatically handle scheduling and cancellation based on internal or external events. User code + * is responsible for calling {@link #run()} periodically to update trigger conditions and execute + * scheduled commands. Most often, this is done by overriding {@link TimedRobot#robotPeriodic()} to + * include a call to {@code Scheduler.getDefault().run()}: + * + *

{@code
+ * public class Robot extends TimedRobot {
+ *   @Override
+ *   public void robotPeriodic() {
+ *     // Update the scheduler on every loop
+ *     Scheduler.getDefault().run();
+ *   }
+ * }
+ * }
+ * + *

Danger

+ * + *

The scheduler must be used in a single-threaded program. Commands must be scheduled and + * cancelled by the same thread that runs the scheduler, and cannot be run in a virtual thread. + * + *

Using the commands framework in a multithreaded environment can cause crashes in the + * Java virtual machine at any time, including on an official field during a match. The + * Java JIT compilers make assumptions that rely on coroutines being used on a single thread. + * Breaking those assumptions can cause incorrect JIT code to be generated with undefined behavior, + * potentially causing control issues or crashes deep in JIT-generated native code. + * + *

Normal concurrency constructs like locks, atomic references, and synchronized blocks + * or methods cannot save you. + * + *

Lifecycle

+ * + *

The {@link #run()} method runs five steps: + * + *

    + *
  1. Poll all registered triggers to queue and cancel commands + *
  2. Call {@link #sideload(Consumer) periodic sideload functions} + *
  3. Start all queued commands. This happens after all triggers are checked in case multiple + * commands with conflicting requirements are queued in the same update; the last command to + * be queued takes precedence over the rest. + *
  4. Loop over all running commands, mounting and calling each in turn until they either exit or + * call {@link Coroutine#yield()}. Commands run in the order in which they were scheduled. + *
  5. Queue default commands for any resources without a running command. The queued commands can + * be superseded by any manual scheduling or commands scheduled by triggers in the next run. + *
+ * + *

Telemetry

+ * + *

There are two mechanisms for telemetry for a scheduler. A protobuf serializer can be used to + * take a snapshot of a scheduler instance, and report what commands are queued (scheduled but have + * not yet started to run), commands that are running (along with timing data for each command), and + * total time spent in the most recent {@link #run()} call. However, it cannot detect one-shot + * commands that are scheduled, run, and complete all in a single {@code run()} invocation - + * effectively, commands that never call {@link Coroutine#yield()} are invisible. + * + *

A second telemetry mechanism is provided by {@link #addEventListener(Consumer)}. The scheduler + * will issue events to all registered listeners when certain events occur (see {@link + * SchedulerEvent} for all event types). These events are emitted immediately and can be used to + * detect lifecycle events for all commands, including one-shots that would be invisible to the + * protobuf serializer. However, it is up to the user to log those events themselves. + */ public class Scheduler implements ProtobufSerializable { private final Map m_defaultCommands = new LinkedHashMap<>(); @@ -63,8 +125,10 @@ public class Scheduler implements ProtobufSerializable { private static final Scheduler s_defaultScheduler = new Scheduler(); /** - * Gets the default scheduler instance for use in a robot program. Some built in command types use - * the default scheduler and will not work as expected if used on another scheduler instance. + * Gets the default scheduler instance for use in a robot program. Unless otherwise specified, + * triggers and resources will be registered with the default scheduler and require the default + * scheduler to run. However, triggers and resources can be constructed to be registered with a + * specific scheduler instance, which may be useful for isolation for unit tests. * * @return the default scheduler instance. */ @@ -437,6 +501,10 @@ private void runCommands() { } } + /** + * Mounts and runs a command until it yields or exits. + * @param state The command state to run + */ @SuppressWarnings("PMD.AvoidCatchingGenericException") private void runCommand(CommandState state) { final var command = state.command(); From 8b0f050152f2bae5905b57b63699075ef5a00d29 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 19:20:31 -0400 Subject: [PATCH 073/153] Make inner continuation reference private --- commandsv3/src/main/java/org/wpilib/commands3/Continuation.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index f9bc699b085..2583c12bb38 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -29,7 +29,7 @@ */ public final class Continuation { // The underlying jdk.internal.vm.Continuation object - final Object m_continuation; + private final Object m_continuation; static final Class jdk_internal_vm_Continuation; private static final MethodHandle CONSTRUCTOR; From b9c45481079b53372a2edd4303539dcece6db12e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 19:53:05 -0400 Subject: [PATCH 074/153] Linting --- commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java | 2 +- commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 9c7d1bf2689..ab753c78d4d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -92,7 +92,7 @@ public void park() { * }

* *

Note: forking a command that conflicts with a higher-priority command will fail. The forked - * command will not be scheduled, and the existing command will continue to run.

+ * command will not be scheduled, and the existing command will continue to run. * * @param commands The commands to fork. */ diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index a9efa97c7f5..169fcf8ac69 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -503,6 +503,7 @@ private void runCommands() { /** * Mounts and runs a command until it yields or exits. + * * @param state The command state to run */ @SuppressWarnings("PMD.AvoidCatchingGenericException") From e36fb91d5cf10634ad5963f27dc0ba6027dd0db2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 7 Aug 2025 23:17:59 -0400 Subject: [PATCH 075/153] Document reasons for using Throwable to get stack frames Also makes both uses consistent --- .../src/main/java/org/wpilib/commands3/Scheduler.java | 2 ++ commandsv3/src/main/java/org/wpilib/commands3/Trigger.java | 7 +++---- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 169fcf8ac69..f33ff8c1ec0 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -247,6 +247,8 @@ public enum ScheduleResult { * scheduled another command that shares at least one required resource */ public ScheduleResult schedule(Command command) { + // Note: we use a throwable here instead of Thread.currentThread().getStackTrace() for easier + // stack frame filtering and modification. var binding = new Binding( BindingScope.global(), BindingType.IMMEDIATE, command, new Throwable().getStackTrace()); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 0ab20ecbcca..d77cc782196 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -328,12 +328,11 @@ private void toggleBindings(BindingType bindingType) { // package-private for testing void addBinding(BindingScope scope, BindingType bindingType, Command command) { - Throwable t = new Throwable("Dummy error to get the binding trace"); - StackTraceElement[] frames = t.getStackTrace(); - + // Note: we use a throwable here instead of Thread.currentThread().getStackTrace() for easier + // stack frame filtering and modification. m_bindings .computeIfAbsent(bindingType, _k -> new ArrayList<>()) - .add(new Binding(scope, bindingType, command, frames)); + .add(new Binding(scope, bindingType, command, new Throwable().getStackTrace())); // Ensure this trigger is bound to the event loop. NOP if already bound m_loop.bind(m_eventLoopCallback); From e26673586a7597b6f5d63c152ee2fb85c2328f42 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 8 Aug 2025 17:14:50 -0400 Subject: [PATCH 076/153] Clean up debounced triggers --- .../src/main/java/org/wpilib/commands3/Trigger.java | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index d77cc782196..f6024770487 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -217,17 +217,8 @@ public Trigger debounce(Time duration) { * @return The debounced trigger. */ public Trigger debounce(Time duration, Debouncer.DebounceType type) { - return new Trigger( - m_scheduler, - m_loop, - new BooleanSupplier() { - final Debouncer m_debouncer = new Debouncer(duration.in(Seconds), type); - - @Override - public boolean getAsBoolean() { - return m_debouncer.calculate(m_condition.getAsBoolean()); - } - }); + var debouncer = new Debouncer(duration.in(Seconds), type); + return new Trigger(m_scheduler, m_loop, () -> debouncer.calculate(m_condition.getAsBoolean())); } private void poll() { From f50fe6e4f5501fd513a13b51fce93181d7d6c4dc Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 9 Aug 2025 12:15:47 -0400 Subject: [PATCH 077/153] Documentation pass on Coroutine; add minor test --- .../java/org/wpilib/commands3/Coroutine.java | 22 ++++++++++++--- .../org/wpilib/commands3/CoroutineTest.java | 27 ++++++++++++++++++- 2 files changed, 44 insertions(+), 5 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index ab753c78d4d..b42572c599b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -14,7 +14,9 @@ /** * A coroutine object is injected into command's {@link Command#run(Coroutine)} method to allow - * commands to yield and compositions to run other commands. + * commands to yield and compositions to run other commands. Commands are considered bound to + * a coroutine while they're scheduled; attempting to use a coroutine outside the command bound to + * it will result in an {@code IllegalStateException} being thrown. */ public final class Coroutine { private final Scheduler m_scheduler; @@ -38,6 +40,7 @@ public final class Coroutine { * as "pausing" the currently executing command. * * @return true + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public boolean yield() { requireMounted(); @@ -63,6 +66,8 @@ public boolean yield() { /** * Parks the current command. No code in a command declared after calling {@code park()} will be * executed. A parked command will never complete naturally and must be interrupted or cancelled. + * + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ @SuppressWarnings("InfiniteLoopStatement") public void park() { @@ -95,6 +100,7 @@ public void park() { * command will not be scheduled, and the existing command will continue to run. * * @param commands The commands to fork. + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void fork(Command... commands) { requireMounted(); @@ -113,8 +119,7 @@ public void fork(Command... commands) { * be scheduled automatically. * * @param command the command to await - * @throws IllegalStateException if the given command uses a resource not owned by the calling - * command + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void await(Command command) { requireMounted(); @@ -134,6 +139,7 @@ public void await(Command command) { * * @param commands the commands to await * @throws IllegalArgumentException if any of the commands conflict with each other + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void awaitAll(Collection commands) { requireMounted(); @@ -157,6 +163,7 @@ public void awaitAll(Collection commands) { * * @param commands the commands to await * @throws IllegalArgumentException if any of the commands conflict with each other + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void awaitAll(Command... commands) { awaitAll(Arrays.asList(commands)); @@ -168,6 +175,7 @@ public void awaitAll(Command... commands) { * * @param commands the commands to await * @throws IllegalArgumentException if any of the commands conflict with each other + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void awaitAny(Collection commands) { requireMounted(); @@ -193,6 +201,7 @@ public void awaitAny(Collection commands) { * * @param commands the commands to await * @throws IllegalArgumentException if any of the commands conflict with each other + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void awaitAny(Command... commands) { awaitAny(Arrays.asList(commands)); @@ -248,6 +257,7 @@ private static void validateNoConflicts(Collection commands) { * }
* * @param duration the duration of time to wait + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void wait(Time duration) { requireMounted(); @@ -259,6 +269,7 @@ public void wait(Time duration) { * Yields until a condition is met. * * @param condition The condition to wait for + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void waitUntil(BooleanSupplier condition) { requireMounted(); @@ -275,8 +286,11 @@ public void waitUntil(BooleanSupplier condition) { * lives longer than the command that scheduled it. * * @return the command scheduler backing this coroutine + * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public Scheduler scheduler() { + requireMounted(); + return m_scheduler; } @@ -294,7 +308,7 @@ private void requireMounted() { return; } - throw new IllegalStateException("Coroutines can only be used while running in a command"); + throw new IllegalStateException("Coroutines can only be used by the command bound to them"); } // Package-private for interaction with the scheduler. diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index b57a8e39943..df9129b748d 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -122,7 +122,32 @@ void coroutineEscapingCommand() { escapeeCallback.get().run(); fail("Calling coroutine.yield() outside of a command should error"); } catch (IllegalStateException expected) { - assertEquals("Coroutines can only be used while running in a command", expected.getMessage()); + assertEquals( + "Coroutines can only be used by the command bound to them", expected.getMessage()); + } + } + + @Test + void usingParentCoroutineInChildThrows() { + var parent = + Command.noRequirements( + parentCoroutine -> { + parentCoroutine.await( + Command.noRequirements( + childCoroutine -> { + parentCoroutine.yield(); + }) + .named("Child")); + }) + .named("Parent"); + + m_scheduler.schedule(parent); + try { + m_scheduler.run(); + fail("Calling parentCoroutine.yield() in a child command should error"); + } catch (IllegalStateException expected) { + assertEquals( + "Coroutines can only be used by the command bound to them", expected.getMessage()); } } From f7972311f8b7303862459e06437aa64b3eb1d780 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 9 Aug 2025 15:37:05 -0400 Subject: [PATCH 078/153] Improve docs for Command.java --- .../java/org/wpilib/commands3/Command.java | 84 +++++++++++-------- 1 file changed, 47 insertions(+), 37 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index faa9dddd04c..ed27eaaa904 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -13,7 +13,7 @@ /** * Performs some task using one or more {@link RequireableResource resources} using the * collaborative concurrency tools added in Java 21; namely, continuations. Continuations allow - * commands to be executed concurrently in a collaborative manner as coroutines. Instead of needing + * commands to be executed concurrently in a collaborative manner as coroutines; instead of needing * to split command behavior into distinct functions (initialize(), execute(), end(), and * isFinished()), commands can be implemented with a single, imperative loop. * @@ -21,50 +21,60 @@ * command implementation must call {@link Coroutine#yield()} within any periodic * loop. Failure to do so may result in an unrecoverable infinite loop. * - *
{@code
- * // A 2013-style class-based command definition
- * class ClassBasedCommand extends Command {
- *   public ClassBasedCommand(Subsystem requiredSubsystem) {
- *     addRequirements(requiredSubsystem);
- *   }
+ * 

Requirements

* - * @Override - * public void initialize() {} + *

Commands require zero or more resources. To prevent conflicting control requests from running + * simultaneously (for example, commanding an elevator to both raise and lower at the same time), a + * running command has exclusive ownership of all of its required resources. If another + * command with an equal or greater {@link #priority()} is scheduled that requires one or more of + * those same resources, it will interrupt and cancel the running command. * - * @Override - * public void execute() {} + *

The recommended way to create a command is using {@link RequireableResource#run(Consumer)} or + * a related factory method to create commands that require a single resource (for example, a + * command that drives an elevator up and down or rotates an arm). Commands may be composed + * into {@link ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex + * behavior out of fundamental building blocks. These built-in compositions will require every + * resource used by every command in them, even if those commands aren't always running, and thus + * can leave certain required resources in an uncommanded state: owned, but not used, this + * can lead to mechanisms sagging under gravity or running the motor control request they were + * given. * - * @Override - * public void end(boolean interrupted) {} + *

Advanced Usage

* - * @Override - * public void isFinished() { return true; } - * - * @Override - * public String getName() { return "The Command"; } - * } + *

For example, a hypothetical drive-and-score sequence could be coded in two ways: one with a + * sequence chain, or one that uses the lower-level coroutine API. Coroutines can be used in an + * async/await style that you may be familiar with from languages like JavaScript, Python, or C# + * (note that there is no {@code async} keyword; commands are inherently asynchronous). Nested + * commands may be forked and awaited, but will not outlive the command that forked them; there is + * no analog for something like a {@code ScheduleCommand} from the v2 commands framework. * - * Command command = new ClassBasedCommand(requiredSubsystem); + *

{@code
+ * class Robot extends TimedRobot {
+ *   private final Drivetrain drivetrain = new Drivetrain();
+ *   private final Elevator elevator = new Elevator();
+ *   private final Gripper gripper = new Gripper();
  *
- * // Or a 2020-style function-based command
- * Command command = requiredSubsystem
- *   .runOnce(() -> initialize())
- *   .andThen(
- *     requiredSubsystem
- *       .run(() -> execute())
- *       .until(() -> isFinished())
- *       .onFinish(() -> end())
- *   ).withName("The Command");
+ *  // Basic sequence builder - owns all 3 mechanisms for the full duration,
+ *  // even when they're not being used
+ *  private Command basicScoringSequence() {
+ *     return drivetrain.driveToScoringLocation()
+ *       .andThen(elevator.moveToScoringHeight())
+ *       .andThen(gripper.release())
+ *       .named("Scoring Sequence (Basic)");
+ *   }
  *
- * // Can be represented with a 2027-style async-based definition
- * Command command = requiredSubsystem.run(coroutine -> {
- *   initialize();
- *   while (!isFinished()) {
- *     coroutine.yield();
- *     execute();
+ *   // Advanced sequence with async/await - only owns mechanisms while they're
+ *   // being used, allowing default commands or other user-triggered commands
+ *   // to run when not in use. Interrupting one of the inner commands while it's
+ *   // running will cancel the entire sequence.
+ *   private Command advancedScoringSequence() {
+ *     return Command.noRequirements(co -> {
+ *       co.await(drivetrain.driveToScoringLocation());
+ *       co.await(elevator.moveToScoringHeight());
+ *       co.await(gripper.release());
+ *     }).named("Scoring Sequence (Advanced)");
  *   }
- *   end();
- * }).named("The Command");
+ * }
  * }
*/ public interface Command { From 244e67e257969195462ef8fe781ae5c8d60278e2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 9 Aug 2025 15:37:16 -0400 Subject: [PATCH 079/153] Note pinned error removal --- commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java | 1 + 1 file changed, 1 insertion(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index b42572c599b..0e1f2f17b40 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -49,6 +49,7 @@ public boolean yield() { return m_backingContinuation.yield(); } catch (IllegalStateException e) { if ("Pinned: MONITOR".equals(e.getMessage())) { + // Note: Not a thing in Java 24+ // Yielding inside a synchronized block or method // Throw with an error message that's more helpful for our users throw new IllegalStateException( From 2cc43f91590ee187711aee315c817a69f2a8a23b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 9 Aug 2025 15:38:13 -0400 Subject: [PATCH 080/153] Remove redundant `this` specifier on members --- .../src/main/java/org/wpilib/commands3/CommandState.java | 4 ++-- .../src/main/java/org/wpilib/commands3/IdleCommand.java | 2 +- .../src/main/java/org/wpilib/commands3/ParallelGroup.java | 4 ++-- .../main/java/org/wpilib/commands3/ParallelGroupBuilder.java | 4 ++-- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index ebde9ff624c..a77d15916a5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -61,7 +61,7 @@ public double lastRuntimeMs() { } public void setLastRuntimeMs(double lastRuntimeMs) { - this.m_lastRuntimeMs = lastRuntimeMs; + m_lastRuntimeMs = lastRuntimeMs; m_totalRuntimeMs += lastRuntimeMs; } @@ -75,7 +75,7 @@ public int id() { @Override public boolean equals(Object obj) { - return obj instanceof CommandState that && this.m_id == that.m_id; + return obj instanceof CommandState that && m_id == that.m_id; } @Override diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index 6eb78c3ac3a..7ef2ab43296 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -54,7 +54,7 @@ public String toString() { @Override public boolean equals(Object obj) { - return obj instanceof IdleCommand other && Objects.equals(this.m_resource, other.m_resource); + return obj instanceof IdleCommand other && Objects.equals(m_resource, other.m_resource); } @Override diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index e33cb39cf24..28a6935433a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -70,8 +70,8 @@ public ParallelGroup( } m_name = name; - this.m_commands.addAll(allCommands); - this.m_requiredCommands.addAll(requiredCommands); + m_commands.addAll(allCommands); + m_requiredCommands.addAll(requiredCommands); for (var command : allCommands) { m_requirements.addAll(command.requirements()); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index b4247b861a4..58e01c07a2f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -28,7 +28,7 @@ public class ParallelGroupBuilder { * @return The builder object, for chaining */ public ParallelGroupBuilder optional(Command... commands) { - this.m_commands.addAll(Arrays.asList(commands)); + m_commands.addAll(Arrays.asList(commands)); return this; } @@ -41,7 +41,7 @@ public ParallelGroupBuilder optional(Command... commands) { */ public ParallelGroupBuilder requiring(Command... commands) { m_requiredCommands.addAll(Arrays.asList(commands)); - this.m_commands.addAll(m_requiredCommands); + m_commands.addAll(m_requiredCommands); return this; } From e2c9650a52d8c0ee7f81d7a935fb4ccd3b5a81ec Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 10 Aug 2025 11:16:48 -0400 Subject: [PATCH 081/153] Fix commands bound to inner triggers outliving the outer command Was caused by the trigger binding not assigning a parent command, allowing commands bound to scoped triggers to outlive the commands that declared those bindings --- .../java/org/wpilib/commands3/Scheduler.java | 10 ++- .../java/org/wpilib/commands3/Trigger.java | 17 ++++- .../org/wpilib/commands3/TriggerTest.java | 64 ++++++++++++++++++- 3 files changed, 88 insertions(+), 3 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index f33ff8c1ec0..d939e0c31f9 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -285,7 +285,15 @@ ScheduleResult schedule(Binding binding) { // so at this point we're guaranteed to be >= priority than anything already on deck evictConflictingOnDeckCommands(command); - var state = new CommandState(command, currentCommand(), buildCoroutine(command), binding); + // If the binding was declared inside a running command, that command is the parent (the current + // command will always be null in this case, since triggers are polled before commands are + // mounted and run). Otherwise, the parent is the command that's running at the time `schedule` + // is called - which may be null. + var parent = + binding.scope() instanceof BindingScope.ForCommand scope + ? scope.command() + : currentCommand(); + var state = new CommandState(command, parent, buildCoroutine(command), binding); emitEvent(SchedulerEvent.scheduled(command)); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index f6024770487..a3ae2acaa09 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -15,15 +15,30 @@ import java.util.List; import java.util.Map; import java.util.function.BooleanSupplier; +import org.wpilib.commands3.button.CommandXboxController; /** - * This class provides an easy way to link commands to conditions. + * Triggers allow users to specify conditions for when commands should run. Triggers can be set up + * to read from joystick and controller buttons (eg {@link CommandXboxController#x()}) or be + * customized to read sensor values or any other arbitrary true/false condition. * *

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. * *

Triggers can easily be composed for advanced functionality using the {@link * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators. + * + *

Trigger bindings created inside a running command will only be active while that command is + * running. This is useful for defining trigger-based behavior only in a certain scope and avoids + * needing to create dozens of global triggers. + * + *

{@code
+ * Command shootWhileAiming = Command.noRequirements(co -> {
+ *   turret.atTarget.onTrue(shooter.shootOnce());
+ *   co.await(turret.lockOnGoal());
+ * }).named("Shoot While Aiming");
+ * controller.rightBumper().whileTrue(shootWhileAiming);
+ * }
*/ public class Trigger implements BooleanSupplier { private final BooleanSupplier m_condition; diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index 18ac8c4e492..89703333304 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -4,9 +4,12 @@ package org.wpilib.commands3; +import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; +import edu.wpi.first.wpilibj.RobotController; +import java.util.List; import java.util.concurrent.atomic.AtomicBoolean; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -17,6 +20,7 @@ class TriggerTest { @BeforeEach void setup() { m_scheduler = new Scheduler(); + RobotController.setTimeSource(() -> System.nanoTime() / 1000); } @Test @@ -147,7 +151,9 @@ void commandScoping() { Command.noRequirements( co -> { new Trigger(m_scheduler, innerSignal::get).onTrue(inner); - co.yield(); + // If we yield, then the outer command exits and immediately cancels the + // on-deck inner command before it can run + co.park(); }) .named("Outer"); @@ -185,4 +191,60 @@ void scopeGoingInactiveCancelsBoundCommand() { m_scheduler.isRunning(command), "Command should have been cancelled when scope became inactive"); } + + // The scheduler lifecycle polls triggers at the start of `run()` + // Even though the trigger condition is set, the command exits and the trigger's scope goes + // inactive before the next `run()` call can poll the trigger + @Test + void triggerFromExitingCommandDoesNotFire() { + var condition = new AtomicBoolean(false); + var triggeredCommandRan = new AtomicBoolean(false); + + var inner = + Command.noRequirements( + co -> { + triggeredCommandRan.set(true); + co.park(); + }) + .named("Inner"); + + var awaited = + Command.noRequirements( + co -> { + co.yield(); + condition.set(true); + }) + .named("Awaited"); + + var outer = + Command.noRequirements( + co -> { + new Trigger(m_scheduler, condition::get).onTrue(inner); + co.await(awaited); + }) + .named("Outer"); + + m_scheduler.schedule(outer); + + // First run: schedules `awaited`, yields + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(outer)); + assertTrue(m_scheduler.isRunning(awaited)); + + // Second run: `awaited` resumes, sets the condition, exits. `outer` exits its final `yield` + // and will exit on the next run. The trigger condition has been set, but the trigger is checked + // on the next call to `run()` + m_scheduler.run(); + assertEquals( + List.of("Outer"), m_scheduler.getRunningCommands().stream().map(Command::name).toList()); + assertTrue(condition.get(), "Condition wasn't set"); + assertFalse(triggeredCommandRan.get(), "Command was unexpectedly triggered"); + + // Third run: trigger binding fires (outside a running command) and queues up `inner`. + // However, the inner command's lifetime is bound to `outer`, and is immediately canceled before + // it can run when the outer command exits. + m_scheduler.run(); + assertEquals(List.of(), m_scheduler.getRunningCommands().stream().map(Command::name).toList()); + assertFalse(triggeredCommandRan.get(), "Command was unexpectedly triggered"); + } } From 7d49e49d85f70e7a6528f023d4236f4b61b31d7a Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 10 Aug 2025 11:39:05 -0400 Subject: [PATCH 082/153] Address new linting warnings from upstream config changes --- commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java | 1 + 1 file changed, 1 insertion(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java index 0b2077ca0ad..3925aca8079 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingScope.java @@ -8,6 +8,7 @@ * A scope for when a binding is live. Bindings tied to a scope must be deleted when the scope * becomes inactive. */ +@SuppressWarnings("PMD.ImplicitFunctionalInterface") interface BindingScope { /** * Checks if the scope is active. Bindings for inactive scopes are removed from the scheduler. From eff9a2b593cce1f25495a1820b1a0d8fc4cfccdf Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 13 Aug 2025 23:50:15 -0400 Subject: [PATCH 083/153] Make cancelAll() also evict on-deck commands --- .../java/org/wpilib/commands3/Scheduler.java | 25 +++++++++---------- .../org/wpilib/commands3/SchedulerTest.java | 16 ++++++++++++ 2 files changed, 28 insertions(+), 13 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index d939e0c31f9..980ea9ea891 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -16,7 +16,6 @@ import java.util.Collection; import java.util.Collections; import java.util.HashSet; -import java.util.Iterator; import java.util.LinkedHashMap; import java.util.LinkedHashSet; import java.util.List; @@ -691,22 +690,22 @@ public List getRunningCommandsFor(RequireableResource resource) { } /** - * Cancels all currently running commands. Commands that are scheduled that haven't yet started - * will remain scheduled, and will start on the next call to {@link #run()}. + * Cancels all currently running and scheduled commands. All default commands will be scheduled on + * the next call to {@link #run()}, unless a higher priority command is scheduled or triggered + * after {@code cancelAll()} is used. */ public void cancelAll() { - // Remove scheduled children of running commands - for (Iterator iterator = m_onDeck.iterator(); iterator.hasNext(); ) { - CommandState state = iterator.next(); - if (m_commandStates.containsKey(state.parent())) { - iterator.remove(); - emitEvent(SchedulerEvent.evicted(state.command())); - } + for (var onDeckIter = m_onDeck.iterator(); onDeckIter.hasNext(); ) { + var state = onDeckIter.next(); + onDeckIter.remove(); + emitEvent(SchedulerEvent.evicted(state.command())); } - // Finally, remove running commands - m_commandStates.forEach((command, _state) -> emitEvent(SchedulerEvent.evicted(command))); - m_commandStates.clear(); + for (var liveIter = m_commandStates.entrySet().iterator(); liveIter.hasNext(); ) { + var entry = liveIter.next(); + liveIter.remove(); + emitEvent(SchedulerEvent.evicted(entry.getKey())); + } } /** diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 41e27a14377..87b9d6f4b22 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -329,6 +329,22 @@ void scheduleOverDefaultDoesNotRescheduleDefault() { assertTrue(m_scheduler.isRunning(defaultCmd)); } + @Test + void cancelsEvictsOnDeck() { + var command = Command.noRequirements(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.cancel(command); + assertFalse(m_scheduler.isScheduledOrRunning(command)); + } + + @Test + void cancelAlEvictsOnDeck() { + var command = Command.noRequirements(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.cancelAll(); + assertFalse(m_scheduler.isScheduledOrRunning(command)); + } + @Test void cancelAllCancelsAll() { var commands = new ArrayList(10); From c84aaec8381029dd05216b5efc956a9e0dc9f180 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 13 Aug 2025 23:53:50 -0400 Subject: [PATCH 084/153] Add tests for deadlock scenarios --- .../org/wpilib/commands3/SchedulerTest.java | 50 +++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 87b9d6f4b22..ff5ab179f16 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -18,6 +18,7 @@ import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; import java.util.function.Supplier; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -879,6 +880,55 @@ void childConflictsWithLowerPriorityTopLevel() { assertTrue(m_scheduler.isRunning(parent), "Parent of conflicting child should be running"); } + @Test + void commandAwaitingItself() { + // This command deadlocks on itself. It's calling yield() in an infinite loop, which is + // equivalent to calling Coroutine.park(). No deleterious side effects other than stalling + // the command + AtomicReference commandRef = new AtomicReference<>(); + var command = Command.noRequirements(co -> co.await(commandRef.get())).named("Self Await"); + commandRef.set(command); + + m_scheduler.schedule(command); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); + } + + @Test + void commandDeadlock() { + AtomicReference ref1 = new AtomicReference<>(); + AtomicReference ref2 = new AtomicReference<>(); + + // Deadlock scenario: + // command1 starts, schedules command2, then waits for command2 to exit + // command2 starts, waits for command1 to exit + // + // Each successive run sees command1 mount, check for command2, then yield. + // Then sees command2 mount, check for command1, then also yield. + // This is like two threads spinwaiting for the other to exit. + // + // Externally cancelling command2 allows command1 to continue + // Externally cancelling command1 cancels both + var command1 = Command.noRequirements(co -> co.await(ref2.get())).named("Command 1"); + var command2 = Command.noRequirements(co -> co.await(ref1.get())).named("Command 2"); + ref1.set(command1); + ref2.set(command2); + + m_scheduler.schedule(command1); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command1)); + assertTrue(m_scheduler.isRunning(command2)); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command1)); + assertTrue(m_scheduler.isRunning(command2)); + + m_scheduler.cancel(command1); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command1)); + assertFalse(m_scheduler.isRunning(command2)); + } + record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { @Override public void run(Coroutine coroutine) { From 2cab4870bf7afb7f82302e0fc3bdd1638709e24a Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 14 Aug 2025 19:24:29 -0400 Subject: [PATCH 085/153] Rename v2 test file to match the class under test --- .../command/{SchedulerTest.java => CommandSchedulerTest.java} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/{SchedulerTest.java => CommandSchedulerTest.java} (99%) diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSchedulerTest.java similarity index 99% rename from wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java rename to wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSchedulerTest.java index 0a6eb3df5ca..2d4a3e4ab9a 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSchedulerTest.java @@ -13,7 +13,7 @@ import java.util.concurrent.atomic.AtomicInteger; import org.junit.jupiter.api.Test; -class SchedulerTest extends CommandTestBase { +class CommandSchedulerTest extends CommandTestBase { @Test void schedulerLambdaTestNoInterrupt() { try (CommandScheduler scheduler = new CommandScheduler()) { From 7115a4633fe3e5f162929c34bc39e8201e61d7f6 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 18:53:35 -0400 Subject: [PATCH 086/153] Rename "RequireableResource" to "Mechanism" --- .../commands3/proto/ProtobufCommand.java | 38 ++-- ...leResource.java => ProtobufMechanism.java} | 64 +++---- .../org/wpilib/commands3/proto/Scheduler.java | 92 +++++----- .../org/wpilib/commands3/BindingType.java | 4 +- .../java/org/wpilib/commands3/Command.java | 36 ++-- .../org/wpilib/commands3/CommandBuilder.java | 46 ++--- .../java/org/wpilib/commands3/Coroutine.java | 6 +- .../org/wpilib/commands3/IdleCommand.java | 22 +-- ...equireableResource.java => Mechanism.java} | 59 +++--- .../org/wpilib/commands3/ParallelGroup.java | 8 +- .../java/org/wpilib/commands3/Scheduler.java | 64 +++---- .../org/wpilib/commands3/SchedulerEvent.java | 4 +- .../java/org/wpilib/commands3/Sequence.java | 10 +- .../org/wpilib/commands3/WaitCommand.java | 2 +- .../wpilib/commands3/proto/CommandProto.java | 4 +- .../commands3/proto/MechanismProto.java | 36 ++++ .../proto/RequireableResourceProto.java | 37 ---- commandsv3/src/main/proto/scheduler.proto | 6 +- .../org/wpilib/commands3/NullCommand.java | 2 +- .../wpilib/commands3/ParallelGroupTest.java | 12 +- .../org/wpilib/commands3/SchedulerTest.java | 168 +++++++++--------- 21 files changed, 365 insertions(+), 355 deletions(-) rename commandsv3/src/generated/main/java/org/wpilib/commands3/proto/{ProtobufRequireableResource.java => ProtobufMechanism.java} (69%) rename commandsv3/src/main/java/org/wpilib/commands3/{RequireableResource.java => Mechanism.java} (55%) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java index 5cda3055792..50b626e1f27 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java @@ -85,12 +85,12 @@ public final class ProtobufCommand extends ProtoMessage impleme /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; */ - private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufRequireableResource.getFactory()); + private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufMechanism.getFactory()); private ProtobufCommand() { } @@ -478,10 +478,10 @@ public ProtobufCommand setName(final Utf8String value) { /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * @return whether the requirements field is set */ public boolean hasRequirements() { @@ -490,10 +490,10 @@ public boolean hasRequirements() { /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * @return this */ public ProtobufCommand clearRequirements() { @@ -504,10 +504,10 @@ public ProtobufCommand clearRequirements() { /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * * This method returns the internal storage object without modifying any has state. * The returned object should not be modified and be treated as read-only. @@ -516,16 +516,16 @@ public ProtobufCommand clearRequirements() { * * @return internal storage object for reading */ - public RepeatedMessage getRequirements() { + public RepeatedMessage getRequirements() { return requirements; } /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * * This method returns the internal storage object and sets the corresponding * has state. The returned object will become part of this message and its @@ -533,21 +533,21 @@ public RepeatedMessage getRequirements() { * * @return internal storage object for modifications */ - public RepeatedMessage getMutableRequirements() { + public RepeatedMessage getMutableRequirements() { bitField0_ |= 0x00000040; return requirements; } /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * @param value the requirements to add * @return this */ - public ProtobufCommand addRequirements(final ProtobufRequireableResource value) { + public ProtobufCommand addRequirements(final ProtobufMechanism value) { bitField0_ |= 0x00000040; requirements.add(value); return this; @@ -555,14 +555,14 @@ public ProtobufCommand addRequirements(final ProtobufRequireableResource value) /** *
-   *  The resources required by the command.
+   *  The mechanisms required by the command.
    * 
* - * repeated .wpi.proto.ProtobufRequireableResource requirements = 5; + * repeated .wpi.proto.ProtobufMechanism requirements = 5; * @param values the requirements to add * @return this */ - public ProtobufCommand addAllRequirements(final ProtobufRequireableResource... values) { + public ProtobufCommand addAllRequirements(final ProtobufMechanism... values) { bitField0_ |= 0x00000040; requirements.addAll(values); return this; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java similarity index 69% rename from commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java rename to commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java index d4430c4fb63..8c631bbe517 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufRequireableResource.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java @@ -17,10 +17,10 @@ import us.hebi.quickbuf.Utf8String; /** - * Protobuf type {@code ProtobufRequireableResource} + * Protobuf type {@code ProtobufMechanism} */ @SuppressWarnings("hiding") -public final class ProtobufRequireableResource extends ProtoMessage implements Cloneable { +public final class ProtobufMechanism extends ProtoMessage implements Cloneable { private static final long serialVersionUID = 0L; /** @@ -28,14 +28,14 @@ public final class ProtobufRequireableResource extends ProtoMessageoptional string name = 1; * @return this */ - public ProtobufRequireableResource clearName() { + public ProtobufMechanism clearName() { bitField0_ &= ~0x00000001; name.clear(); return this; @@ -86,7 +86,7 @@ public Utf8String getMutableNameBytes() { * @param value the name to set * @return this */ - public ProtobufRequireableResource setName(final CharSequence value) { + public ProtobufMechanism setName(final CharSequence value) { bitField0_ |= 0x00000001; name.copyFrom(value); return this; @@ -97,14 +97,14 @@ public ProtobufRequireableResource setName(final CharSequence value) { * @param value the name to set * @return this */ - public ProtobufRequireableResource setName(final Utf8String value) { + public ProtobufMechanism setName(final Utf8String value) { bitField0_ |= 0x00000001; name.copyFrom(value); return this; } @Override - public ProtobufRequireableResource copyFrom(final ProtobufRequireableResource other) { + public ProtobufMechanism copyFrom(final ProtobufMechanism other) { cachedSize = other.cachedSize; if ((bitField0_ | other.bitField0_) != 0) { bitField0_ = other.bitField0_; @@ -114,7 +114,7 @@ public ProtobufRequireableResource copyFrom(final ProtobufRequireableResource ot } @Override - public ProtobufRequireableResource mergeFrom(final ProtobufRequireableResource other) { + public ProtobufMechanism mergeFrom(final ProtobufMechanism other) { if (other.isEmpty()) { return this; } @@ -126,7 +126,7 @@ public ProtobufRequireableResource mergeFrom(final ProtobufRequireableResource o } @Override - public ProtobufRequireableResource clear() { + public ProtobufMechanism clear() { if (isEmpty()) { return this; } @@ -137,7 +137,7 @@ public ProtobufRequireableResource clear() { } @Override - public ProtobufRequireableResource clearQuick() { + public ProtobufMechanism clearQuick() { if (isEmpty()) { return this; } @@ -152,10 +152,10 @@ public boolean equals(Object o) { if (o == this) { return true; } - if (!(o instanceof ProtobufRequireableResource)) { + if (!(o instanceof ProtobufMechanism)) { return false; } - ProtobufRequireableResource other = (ProtobufRequireableResource) o; + ProtobufMechanism other = (ProtobufMechanism) o; return bitField0_ == other.bitField0_ && (!hasName() || name.equals(other.name)); } @@ -179,7 +179,7 @@ protected int computeSerializedSize() { @Override @SuppressWarnings("fallthrough") - public ProtobufRequireableResource mergeFrom(final ProtoSource input) throws IOException { + public ProtobufMechanism mergeFrom(final ProtoSource input) throws IOException { // Enabled Fall-Through Optimization (QuickBuffers) int tag = input.readTag(); while (true) { @@ -217,7 +217,7 @@ public void writeTo(final JsonSink output) throws IOException { } @Override - public ProtobufRequireableResource mergeFrom(final JsonSource input) throws IOException { + public ProtobufMechanism mergeFrom(final JsonSource input) throws IOException { if (!input.beginObject()) { return this; } @@ -245,8 +245,8 @@ public ProtobufRequireableResource mergeFrom(final JsonSource input) throws IOEx } @Override - public ProtobufRequireableResource clone() { - return new ProtobufRequireableResource().copyFrom(this); + public ProtobufMechanism clone() { + return new ProtobufMechanism().copyFrom(this); } @Override @@ -254,39 +254,39 @@ public boolean isEmpty() { return ((bitField0_) == 0); } - public static ProtobufRequireableResource parseFrom(final byte[] data) throws + public static ProtobufMechanism parseFrom(final byte[] data) throws InvalidProtocolBufferException { - return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), data).checkInitialized(); + return ProtoMessage.mergeFrom(new ProtobufMechanism(), data).checkInitialized(); } - public static ProtobufRequireableResource parseFrom(final ProtoSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), input).checkInitialized(); + public static ProtobufMechanism parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); } - public static ProtobufRequireableResource parseFrom(final JsonSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufRequireableResource(), input).checkInitialized(); + public static ProtobufMechanism parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); } /** - * @return factory for creating ProtobufRequireableResource messages + * @return factory for creating ProtobufMechanism messages */ - public static MessageFactory getFactory() { - return ProtobufRequireableResourceFactory.INSTANCE; + public static MessageFactory getFactory() { + return ProtobufMechanismFactory.INSTANCE; } /** * @return this type's descriptor. */ public static Descriptors.Descriptor getDescriptor() { - return Scheduler.wpi_proto_ProtobufRequireableResource_descriptor; + return Scheduler.wpi_proto_ProtobufMechanism_descriptor; } - private enum ProtobufRequireableResourceFactory implements MessageFactory { + private enum ProtobufMechanismFactory implements MessageFactory { INSTANCE; @Override - public ProtobufRequireableResource create() { - return ProtobufRequireableResource.newInstance(); + public ProtobufMechanism create() { + return ProtobufMechanism.newInstance(); } } diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java index 613232c0ae5..6806fb867be 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java @@ -9,57 +9,57 @@ import us.hebi.quickbuf.RepeatedByte; public final class Scheduler { - private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2495, - "Cg9zY2hlZHVsZXIucHJvdG8SCXdwaS5wcm90byIxChtQcm90b2J1ZlJlcXVpcmVhYmxlUmVzb3VyY2US" + - "EgoEbmFtZRgBIAEoCVIEbmFtZSLAAgoPUHJvdG9idWZDb21tYW5kEg4KAmlkGAEgASgNUgJpZBIgCglw" + - "YXJlbnRfaWQYAiABKA1IAFIIcGFyZW50SWSIAQESEgoEbmFtZRgDIAEoCVIEbmFtZRIaCghwcmlvcml0" + - "eRgEIAEoBVIIcHJpb3JpdHkSSgoMcmVxdWlyZW1lbnRzGAUgAygLMiYud3BpLnByb3RvLlByb3RvYnVm" + - "UmVxdWlyZWFibGVSZXNvdXJjZVIMcmVxdWlyZW1lbnRzEiUKDGxhc3RfdGltZV9tcxgGIAEoAUgBUgps" + - "YXN0VGltZU1ziAEBEicKDXRvdGFsX3RpbWVfbXMYByABKAFIAlILdG90YWxUaW1lTXOIAQFCDAoKX3Bh" + - "cmVudF9pZEIPCg1fbGFzdF90aW1lX21zQhAKDl90b3RhbF90aW1lX21zIsEBChFQcm90b2J1ZlNjaGVk" + - "dWxlchJDCg9xdWV1ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg5x" + - "dWV1ZWRDb21tYW5kcxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnByb3RvLlByb3RvYnVm" + - "Q29tbWFuZFIPcnVubmluZ0NvbW1hbmRzEiAKDGxhc3RfdGltZV9tcxgDIAEoAVIKbGFzdFRpbWVNc0Ie" + - "Chpvcmcud3BpbGliLmNvbW1hbmRzMy5wcm90b1ABSr4OCgYSBAAANQEKCAoBDBIDAAASCggKAQISAwIA" + - "EgoICgEIEgMEADMKCQoCCAESAwQAMwoICgEIEgMFACIKCQoCCAoSAwUAIgqfAQoCBAASBA0ADwEykgEK" + - "YWxsd3BpbGliICQgcHJvdG9jLXF1aWNrYnVmIFwKLS1xdWlja2J1Zl9vdXQ9Z2VuX2Rlc2NyaXB0b3Jz" + - "PXRydWU6Y29tbWFuZHN2My9zcmMvZ2VuZXJhdGVkL21haW4vamF2YSBcCmNvbW1hbmRzdjMvc3JjL21h" + - "aW4vcHJvdG8vc2NoZWR1bGVyLnByb3RvCgoKCgMEAAESAw0IIwoLCgQEAAIAEgMOAhIKDAoFBAACAAUS" + - "Aw4CCAoMCgUEAAIAARIDDgkNCgwKBQQAAgADEgMOEBEKCgoCBAESBBEAKgEKCgoDBAEBEgMRCBcKcQoE" + - "BAECABIDFAIQGmQgQSB1bmlxdWUgSUQgZm9yIHRoZSBjb21tYW5kLgogRGlmZmVyZW50IGludm9jYXRp" + - "b25zIG9mIHRoZSBzYW1lIGNvbW1hbmQgb2JqZWN0IGhhdmUgZGlmZmVyZW50IElEcy4KCgwKBQQBAgAF" + - "EgMUAggKDAoFBAECAAESAxQJCwoMCgUEAQIAAxIDFA4PCmEKBAQBAgESAxgCIBpUIFRoZSBJRCBvZiB0" + - "aGUgcGFyZW50IGNvbW1hbmQuCiBOb3QgaW5jbHVkZWQgaW4gdGhlIG1lc3NhZ2UgZm9yIHRvcC1sZXZl", - "bCBjb21tYW5kcy4KCgwKBQQBAgEEEgMYAgoKDAoFBAECAQUSAxgLEQoMCgUEAQIBARIDGBIbCgwKBQQB" + - "AgEDEgMYHh8KJwoEBAECAhIDGwISGhogVGhlIG5hbWUgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQICBRID" + - "GwIICgwKBQQBAgIBEgMbCQ0KDAoFBAECAgMSAxsQEQoxCgQEAQIDEgMeAhUaJCBUaGUgcHJpb3JpdHkg" + - "bGV2ZWwgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQIDBRIDHgIHCgwKBQQBAgMBEgMeCBAKDAoFBAECAwMS" + - "Ax4TFAo1CgQEAQIEEgMhAjgaKCBUaGUgcmVzb3VyY2VzIHJlcXVpcmVkIGJ5IHRoZSBjb21tYW5kLgoK" + - "DAoFBAECBAQSAyECCgoMCgUEAQIEBhIDIQsmCgwKBQQBAgQBEgMhJzMKDAoFBAECBAMSAyE2NwqOAQoE" + - "BAECBRIDJQIjGoABIEhvdyBtdWNoIHRpbWUgdGhlIGNvbW1hbmQgdG9vayB0byBleGVjdXRlIGluIGl0" + - "cyBtb3N0IHJlY2VudCBydW4uCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZl" + - "bHkgcnVubmluZyBjb21tYW5kLgoKDAoFBAECBQQSAyUCCgoMCgUEAQIFBRIDJQsRCgwKBQQBAgUBEgMl" + - "Eh4KDAoFBAECBQMSAyUhIgqAAQoEBAECBhIDKQIkGnMgSG93IGxvbmcgdGhlIGNvbW1hbmQgaGFzIHRh" + - "a2VuIHRvIHJ1biwgaW4gYWdncmVnYXRlLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFu" + - "IGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgYEEgMpAgoKDAoFBAECBgUSAykLEQoMCgUE" + - "AQIGARIDKRIfCgwKBQQBAgYDEgMpIiMKCgoCBAISBCwANQEKCgoDBAIBEgMsCBkKjQIKBAQCAgASAzAC" + - "Lxr/ASBOb3RlOiBjb21tYW5kcyBhcmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2gg" + - "b2NjdXJzIGltbWVkaWF0ZWx5IGJlZm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5p" + - "bmcuIEVudHJpZXMgd2lsbCBvbmx5IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVs" + - "ZXIKIF9hZnRlcl8gbWFudWFsbHkgc2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxp" + - "bmcgc2NoZWR1bGVyLnJ1bigpCgoMCgUEAgIABBIDMAIKCgwKBQQCAgAGEgMwCxoKDAoFBAICAAESAzAb" + - "KgoMCgUEAgIAAxIDMC0uCgsKBAQCAgESAzECMAoMCgUEAgIBBBIDMQIKCgwKBQQCAgEGEgMxCxoKDAoF" + - "BAICAQESAzEbKwoMCgUEAgIBAxIDMS4vCk8KBAQCAgISAzQCGhpCIEhvdyBtdWNoIHRpbWUgdGhlIHNj", - "aGVkdWxlciB0b29rIGluIGl0cyBsYXN0IGBydW4oKWAgaW52b2NhdGlvbi4KCgwKBQQCAgIFEgM0AggK" + - "DAoFBAICAgESAzQJFQoMCgUEAgICAxIDNBgZYgZwcm90bzM="); + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2476, + "Cg9zY2hlZHVsZXIucHJvdG8SCXdwaS5wcm90byInChFQcm90b2J1Zk1lY2hhbmlzbRISCgRuYW1lGAEg" + + "ASgJUgRuYW1lIrYCCg9Qcm90b2J1ZkNvbW1hbmQSDgoCaWQYASABKA1SAmlkEiAKCXBhcmVudF9pZBgC" + + "IAEoDUgAUghwYXJlbnRJZIgBARISCgRuYW1lGAMgASgJUgRuYW1lEhoKCHByaW9yaXR5GAQgASgFUghw" + + "cmlvcml0eRJACgxyZXF1aXJlbWVudHMYBSADKAsyHC53cGkucHJvdG8uUHJvdG9idWZNZWNoYW5pc21S" + + "DHJlcXVpcmVtZW50cxIlCgxsYXN0X3RpbWVfbXMYBiABKAFIAVIKbGFzdFRpbWVNc4gBARInCg10b3Rh" + + "bF90aW1lX21zGAcgASgBSAJSC3RvdGFsVGltZU1ziAEBQgwKCl9wYXJlbnRfaWRCDwoNX2xhc3RfdGlt" + + "ZV9tc0IQCg5fdG90YWxfdGltZV9tcyLBAQoRUHJvdG9idWZTY2hlZHVsZXISQwoPcXVldWVkX2NvbW1h" + + "bmRzGAEgAygLMhoud3BpLnByb3RvLlByb3RvYnVmQ29tbWFuZFIOcXVldWVkQ29tbWFuZHMSRQoQcnVu" + + "bmluZ19jb21tYW5kcxgCIAMoCzIaLndwaS5wcm90by5Qcm90b2J1ZkNvbW1hbmRSD3J1bm5pbmdDb21t" + + "YW5kcxIgCgxsYXN0X3RpbWVfbXMYAyABKAFSCmxhc3RUaW1lTXNCHgoab3JnLndwaWxpYi5jb21tYW5k" + + "czMucHJvdG9QAUq/DgoGEgQAADUBCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAzCgkKAggBEgME" + + "ADMKCAoBCBIDBQAiCgkKAggKEgMFACIKnwEKAgQAEgQNAA8BMpIBCmFsbHdwaWxpYiAkIHByb3RvYy1x" + + "dWlja2J1ZiBcCi0tcXVpY2tidWZfb3V0PWdlbl9kZXNjcmlwdG9ycz10cnVlOmNvbW1hbmRzdjMvc3Jj" + + "L2dlbmVyYXRlZC9tYWluL2phdmEgXApjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5w" + + "cm90bwoKCgoDBAABEgMNCBkKCwoEBAACABIDDgISCgwKBQQAAgAFEgMOAggKDAoFBAACAAESAw4JDQoM" + + "CgUEAAIAAxIDDhARCgoKAgQBEgQRACoBCgoKAwQBARIDEQgXCnEKBAQBAgASAxQCEBpkIEEgdW5pcXVl" + + "IElEIGZvciB0aGUgY29tbWFuZC4KIERpZmZlcmVudCBpbnZvY2F0aW9ucyBvZiB0aGUgc2FtZSBjb21t" + + "YW5kIG9iamVjdCBoYXZlIGRpZmZlcmVudCBJRHMuCgoMCgUEAQIABRIDFAIICgwKBQQBAgABEgMUCQsK" + + "DAoFBAECAAMSAxQODwphCgQEAQIBEgMYAiAaVCBUaGUgSUQgb2YgdGhlIHBhcmVudCBjb21tYW5kLgog" + + "Tm90IGluY2x1ZGVkIGluIHRoZSBtZXNzYWdlIGZvciB0b3AtbGV2ZWwgY29tbWFuZHMuCgoMCgUEAQIB", + "BBIDGAIKCgwKBQQBAgEFEgMYCxEKDAoFBAECAQESAxgSGwoMCgUEAQIBAxIDGB4fCicKBAQBAgISAxsC" + + "EhoaIFRoZSBuYW1lIG9mIHRoZSBjb21tYW5kLgoKDAoFBAECAgUSAxsCCAoMCgUEAQICARIDGwkNCgwK" + + "BQQBAgIDEgMbEBEKMQoEBAECAxIDHgIVGiQgVGhlIHByaW9yaXR5IGxldmVsIG9mIHRoZSBjb21tYW5k" + + "LgoKDAoFBAECAwUSAx4CBwoMCgUEAQIDARIDHggQCgwKBQQBAgMDEgMeExQKNgoEBAECBBIDIQIuGikg" + + "VGhlIG1lY2hhbmlzbXMgcmVxdWlyZWQgYnkgdGhlIGNvbW1hbmQuCgoMCgUEAQIEBBIDIQIKCgwKBQQB" + + "AgQGEgMhCxwKDAoFBAECBAESAyEdKQoMCgUEAQIEAxIDISwtCo4BCgQEAQIFEgMlAiMagAEgSG93IG11" + + "Y2ggdGltZSB0aGUgY29tbWFuZCB0b29rIHRvIGV4ZWN1dGUgaW4gaXRzIG1vc3QgcmVjZW50IHJ1bi4K" + + "IE9ubHkgaW5jbHVkZWQgaW4gYSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQu" + + "CgoMCgUEAQIFBBIDJQIKCgwKBQQBAgUFEgMlCxEKDAoFBAECBQESAyUSHgoMCgUEAQIFAxIDJSEiCoAB" + + "CgQEAQIGEgMpAiQacyBIb3cgbG9uZyB0aGUgY29tbWFuZCBoYXMgdGFrZW4gdG8gcnVuLCBpbiBhZ2dy" + + "ZWdhdGUuCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZlbHkgcnVubmluZyBj" + + "b21tYW5kLgoKDAoFBAECBgQSAykCCgoMCgUEAQIGBRIDKQsRCgwKBQQBAgYBEgMpEh8KDAoFBAECBgMS" + + "AykiIwoKCgIEAhIELAA1AQoKCgMEAgESAywIGQqNAgoEBAICABIDMAIvGv8BIE5vdGU6IGNvbW1hbmRz" + + "IGFyZSBnZW5lcmFsbHkgcXVldWVkIGJ5IHRyaWdnZXJzLCB3aGljaCBvY2N1cnMgaW1tZWRpYXRlbHkg" + + "YmVmb3JlIHRoZXkgYXJlCiBwcm9tb3RlZCBhbmQgc3RhcnQgcnVubmluZy4gRW50cmllcyB3aWxsIG9u" + + "bHkgYXBwZWFyIGhlcmUgd2hlbiBzZXJpYWxpemluZyBhIHNjaGVkdWxlcgogX2FmdGVyXyBtYW51YWxs" + + "eSBzY2hlZHVsaW5nIGEgY29tbWFuZCBidXQgX2JlZm9yZV8gY2FsbGluZyBzY2hlZHVsZXIucnVuKCkK" + + "CgwKBQQCAgAEEgMwAgoKDAoFBAICAAYSAzALGgoMCgUEAgIAARIDMBsqCgwKBQQCAgADEgMwLS4KCwoE" + + "BAICARIDMQIwCgwKBQQCAgEEEgMxAgoKDAoFBAICAQYSAzELGgoMCgUEAgIBARIDMRsrCgwKBQQCAgED" + + "EgMxLi8KTwoEBAICAhIDNAIaGkIgSG93IG11Y2ggdGltZSB0aGUgc2NoZWR1bGVyIHRvb2sgaW4gaXRz", + "IGxhc3QgYHJ1bigpYCBpbnZvY2F0aW9uLgoKDAoFBAICAgUSAzQCCAoMCgUEAgICARIDNAkVCgwKBQQC" + + "AgIDEgM0GBliBnByb3RvMw=="); static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("scheduler.proto", "wpi.proto", descriptorData); - static final Descriptors.Descriptor wpi_proto_ProtobufRequireableResource_descriptor = descriptor.internalContainedType(30, 49, "ProtobufRequireableResource", "wpi.proto.ProtobufRequireableResource"); + static final Descriptors.Descriptor wpi_proto_ProtobufMechanism_descriptor = descriptor.internalContainedType(30, 39, "ProtobufMechanism", "wpi.proto.ProtobufMechanism"); - static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(82, 320, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(72, 310, "ProtobufCommand", "wpi.proto.ProtobufCommand"); - static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(405, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(385, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); /** * @return this proto file's descriptor. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java index 525d4bb56e5..e3f5b84f1cd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java @@ -13,12 +13,12 @@ enum BindingType { IMMEDIATE, /** * Schedules (forks) a command on a rising edge signal. The command will run until it completes or - * is interrupted by another command requiring the same resources. + * is interrupted by another command requiring the same mechanisms. */ SCHEDULE_ON_RISING_EDGE, /** * Schedules (forks) a command on a falling edge signal. The command will run until it completes - * or is interrupted by another command requiring the same resources. + * or is interrupted by another command requiring the same mechanisms. */ SCHEDULE_ON_FALLING_EDGE, /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index ed27eaaa904..12d2455d840 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -11,7 +11,7 @@ import java.util.function.Consumer; /** - * Performs some task using one or more {@link RequireableResource resources} using the + * Performs some task using one or more {@link Mechanism resources} using the * collaborative concurrency tools added in Java 21; namely, continuations. Continuations allow * commands to be executed concurrently in a collaborative manner as coroutines; instead of needing * to split command behavior into distinct functions (initialize(), execute(), end(), and @@ -29,7 +29,7 @@ * command with an equal or greater {@link #priority()} is scheduled that requires one or more of * those same resources, it will interrupt and cancel the running command. * - *

The recommended way to create a command is using {@link RequireableResource#run(Consumer)} or + *

The recommended way to create a command is using {@link Mechanism#run(Consumer)} or * a related factory method to create commands that require a single resource (for example, a * command that drives an elevator up and down or rotates an arm). Commands may be composed * into {@link ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex @@ -122,13 +122,13 @@ default void onCancel() { String name(); /** - * The set of resources required by the command. This is used by the scheduler to determine if two - * commands conflict with each other. Any singular resource may only be required by a single + * The mechanisms required by the command. This is used by the scheduler to determine if two + * commands conflict with each other. Any singular mechanism may only be required by a single * running command at a time. * - * @return the set of resources required by the command + * @return the set of mechanisms required by the command */ - Set requirements(); + Set requirements(); /** * The priority of the command. If a command is scheduled that conflicts with another running or @@ -154,20 +154,20 @@ default boolean isLowerPriorityThan(Command other) { } /** - * Checks if this command requires a particular resource. + * Checks if this command requires a particular mechanism. * - * @param resource the resource to check - * @return true if the resource is a member of the required resources, false if not + * @param mechanism the mechanism to check + * @return true if the mechanism is a member of the required mechanisms, false if not */ - default boolean requires(RequireableResource resource) { - return requirements().contains(resource); + default boolean requires(Mechanism mechanism) { + return requirements().contains(mechanism); } /** * Checks if this command conflicts with another command. * * @param other the commands to check against - * @return true if both commands require at least one of the same resource, false if both commands + * @return true if both commands require at least one of the same mechanism, false if both commands * have completely different requirements */ default boolean conflictsWith(Command other) { @@ -194,7 +194,7 @@ default Command withTimeout(Time timeout) { * Creates a command that does not require any hardware; that is, it does not affect the state of * any physical objects. This is useful for commands that do some house cleaning work like * resetting odometry and sensors that you don't want to interrupt a command that's controlling - * the resources it affects. + * the mechanisms it affects. * * @param impl the implementation of the command logic * @return a builder that can be used to configure the resulting command @@ -204,13 +204,13 @@ static CommandBuilder noRequirements(Consumer impl) { } /** - * Starts creating a command that requires one or more resources. + * Starts creating a command that requires one or more mechanisms. * - * @param requirement The first required resource - * @param rest Any other required resources + * @param requirement The first required mechanism + * @param rest Any other required mechanisms * @return A command builder */ - static CommandBuilder requiring(RequireableResource requirement, RequireableResource... rest) { + static CommandBuilder requiring(Mechanism requirement, Mechanism... rest) { return new CommandBuilder().requiring(requirement).requiring(rest); } @@ -252,7 +252,7 @@ static SequenceBuilder sequence(Command... commands) { /** * Starts creating a command that simply waits for some condition to be met. The command will * start without any requirements, but some may be added (if necessary) using {@link - * CommandBuilder#requiring(RequireableResource)}. + * CommandBuilder#requiring(Mechanism)}. * * @param condition The condition to wait for * @return A command builder diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java index f1a9816b57d..767432094b6 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java @@ -19,7 +19,7 @@ * A builder that allows for all functionality of a command to be configured prior to creating it. */ public class CommandBuilder { - private final Set m_requirements = new HashSet<>(); + private final Set m_requirements = new HashSet<>(); private Consumer m_impl; private Runnable m_onCancel = () -> {}; private String m_name; @@ -27,57 +27,57 @@ public class CommandBuilder { private BooleanSupplier m_endCondition; /** - * Adds a resource as a requirement for the command. + * Adds a mechanism as a requirement for the command. * - * @param resource The required resource + * @param mechanism The required mechanism * @return The builder object, for chaining * @see Command#requirements() */ - public CommandBuilder requiring(RequireableResource resource) { - requireNonNullParam(resource, "resource", "CommandBuilder.requiring"); + public CommandBuilder requiring(Mechanism mechanism) { + requireNonNullParam(mechanism, "mechanism", "CommandBuilder.requiring"); - m_requirements.add(resource); + m_requirements.add(mechanism); return this; } /** - * Adds resources as requirements for the command. + * Adds mechanisms as requirements for the command. * - * @param resources The required resources + * @param mechanisms The required mechanisms * @return The builder object, for chaining * @see Command#requirements() */ - public CommandBuilder requiring(RequireableResource... resources) { - requireNonNullParam(resources, "resources", "CommandBuilder.requiring"); - for (int i = 0; i < resources.length; i++) { - requireNonNullParam(resources[i], "resources[" + i + "]", "CommandBuilder.requiring"); + public CommandBuilder requiring(Mechanism... mechanisms) { + requireNonNullParam(mechanisms, "mechanisms", "CommandBuilder.requiring"); + for (int i = 0; i < mechanisms.length; i++) { + requireNonNullParam(mechanisms[i], "mechanisms[" + i + "]", "CommandBuilder.requiring"); } - m_requirements.addAll(Arrays.asList(resources)); + m_requirements.addAll(Arrays.asList(mechanisms)); return this; } /** - * Adds resources as requirements for the command. + * Adds mechanisms as requirements for the command. * - * @param resources The required resources + * @param mechanisms The required mechanisms * @return The builder object, for chaining * @see Command#requirements() */ - public CommandBuilder requiring(Collection resources) { - requireNonNullParam(resources, "resources", "CommandBuilder.requiring"); - if (resources instanceof List l) { + public CommandBuilder requiring(Collection mechanisms) { + requireNonNullParam(mechanisms, "mechanisms", "CommandBuilder.requiring"); + if (mechanisms instanceof List l) { for (int i = 0; i < l.size(); i++) { - requireNonNullParam(l.get(i), "resources[" + i + "]", "CommandBuilder.requiring"); + requireNonNullParam(l.get(i), "mechanisms[" + i + "]", "CommandBuilder.requiring"); } } else { // non-indexable collection - for (var resource : resources) { - requireNonNullParam(resource, "resources", "CommandBuilder.requiring"); + for (var mechanism : mechanisms) { + requireNonNullParam(mechanism, "mechanisms", "CommandBuilder.requiring"); } } - m_requirements.addAll(resources); + m_requirements.addAll(mechanisms); return this; } @@ -199,7 +199,7 @@ public String name() { } @Override - public Set requirements() { + public Set requirements() { return m_requirements; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 0e1f2f17b40..920b77a85b9 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -214,7 +214,7 @@ public void awaitAny(Command... commands) { * * @param commands The commands to validate * @throws IllegalArgumentException If at least one pair of commands is found in the input where - * both commands have at least one required resource in common + * both commands have at least one required mechanism in common */ @SuppressWarnings("PMD.CompareObjectsWithEquals") private static void validateNoConflicts(Collection commands) { @@ -230,11 +230,11 @@ private static void validateNoConflicts(Collection commands) { var conflictNames = c1.requirements().stream() .filter(c2::requires) - .map(RequireableResource::getName) + .map(Mechanism::getName) .collect(Collectors.joining(", ")); throw new IllegalArgumentException( - "Command %s requires resources that are already used by %s. Both require %s" + "Command %s requires mechanisms that are already used by %s. Both require %s" .formatted(c2.name(), c1.name(), conflictNames)); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index 7ef2ab43296..f3e6c98889c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -10,20 +10,20 @@ import java.util.Set; /** - * An idle command that owns a resource without doing anything. It has the lowest possible priority, - * and can be interrupted by any other command that requires the same resource. Cancellation and + * An idle command that owns a mechanism without doing anything. It has the lowest possible priority, + * and can be interrupted by any other command that requires the same mechanism. Cancellation and * interruption function like a normal command. */ public final class IdleCommand implements Command { - private final RequireableResource m_resource; + private final Mechanism m_mechanism; /** * Creates a new idle command. * - * @param resource the resource to idle. + * @param mechanism the mechanism to idle. */ - public IdleCommand(RequireableResource resource) { - m_resource = requireNonNullParam(resource, "resource", "IdleCommand"); + public IdleCommand(Mechanism mechanism) { + m_mechanism = requireNonNullParam(mechanism, "mechanism", "IdleCommand"); } @Override @@ -32,13 +32,13 @@ public void run(Coroutine coroutine) { } @Override - public Set requirements() { - return Set.of(m_resource); + public Set requirements() { + return Set.of(m_mechanism); } @Override public String name() { - return m_resource.getName() + "[IDLE]"; + return m_mechanism.getName() + "[IDLE]"; } @Override @@ -54,11 +54,11 @@ public String toString() { @Override public boolean equals(Object obj) { - return obj instanceof IdleCommand other && Objects.equals(m_resource, other.m_resource); + return obj instanceof IdleCommand other && Objects.equals(m_mechanism, other.m_mechanism); } @Override public int hashCode() { - return Objects.hash(m_resource); + return Objects.hash(m_mechanism); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java similarity index 55% rename from commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java rename to commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index c9c57b97c52..2585e0c4c90 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/RequireableResource.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -9,61 +9,71 @@ import java.util.function.Consumer; /** - * A resource that may be claimed by a command. A single claimable resource cannot be claimed by - * more than one running command at a time. + * Generic base class to represent mechanisms on a robot. Commands can require sole ownership of a + * mechanism; when a command that requires a mechanism is running, no other commands may use it at + * the same time. + * + *

Even though this class is named "Mechanism", it may be used to represent other physical + * hardware on a robot that should be controlled with commands - for example, an LED strip or a + * vision processor that can switch between different pipelines could be represented as mechanisms. */ -public class RequireableResource { +public class Mechanism { private final String m_name; private final Scheduler m_registeredScheduler; /** - * Creates a new requireable resource registered with the default scheduler instance and named + * Creates a new mechanism registered with the default scheduler instance and named * using the name of the class. Intended to be used by subclasses to get sane defaults without * needing to manually declare a constructor. */ @SuppressWarnings("this-escape") - protected RequireableResource() { + protected Mechanism() { m_name = getClass().getSimpleName(); m_registeredScheduler = Scheduler.getDefault(); setDefaultCommand(idle()); } /** - * Creates a new claimable resource, registered with the default scheduler instance. + * Creates a new mechanism, registered with the default scheduler instance. * - * @param name The name of the resource. Cannot be null. + * @param name The name of the mechanism. Cannot be null. */ - public RequireableResource(String name) { + public Mechanism(String name) { this(name, Scheduler.getDefault()); } /** - * Creates a new claimable resource, registered with the given scheduler instance. + * Creates a new mechanism, registered with the given scheduler instance. * - * @param name The name of the resource. Cannot be null. + * @param name The name of the mechanism. Cannot be null. * @param scheduler The registered scheduler. Cannot be null. */ @SuppressWarnings("this-escape") - public RequireableResource(String name, Scheduler scheduler) { + public Mechanism(String name, Scheduler scheduler) { m_name = name; m_registeredScheduler = scheduler; setDefaultCommand(idle()); } + /** + * Gets the name of this mechanism. + * + * @return The name of the mechanism. + */ public String getName() { return m_name; } /** - * Sets the default command to run on the resource when no other command is scheduled. The default - * command's priority is effectively the minimum allowable priority for any command requiring a - * resource. For this reason, it's required that a default command have a priority less than - * {@link Command#DEFAULT_PRIORITY} to prevent it from blocking other, non-default commands from - * running. + * Sets the default command to run on the mechanism when no other command is scheduled. The + * default command's priority is effectively the minimum allowable priority for any command + * requiring a mechanism. For this reason, it's recommended that a default command have a priority + * less than{@link Command#DEFAULT_PRIORITY} to prevent it from blocking other, non-default + * commands from running. * - *

The default command is initially an idle command that merely parks the execution thread. - * This command has the lowest possible priority so as to allow any other command to run. + *

The default command is initially an idle command that only owns the mechanism without doing + * anything. This command has the lowest possible priority to allow any other command to run. * * @param defaultCommand the new default command */ @@ -82,7 +92,7 @@ public Command getDefaultCommand() { } /** - * Starts building a command that requires this resource. + * Starts building a command that requires this mechanism. * * @param commandBody The main function body of the command. * @return The command builder, for further configuration. @@ -92,7 +102,7 @@ public CommandBuilder run(Consumer commandBody) { } /** - * Starts building a command that requires this resource. The given function will be called + * Starts building a command that requires this mechanism. The given function will be called * repeatedly in an infinite loop. Useful for building commands that don't need state or multiple * stages of logic. * @@ -110,11 +120,12 @@ public CommandBuilder runRepeatedly(Runnable loopBody) { } /** - * Returns a command that idles this resource until another command claims it. The idle command + * Returns a command that idles this mechanism until another command claims it. The idle command * has {@link Command#LOWEST_PRIORITY the lowest priority} and can be interrupted by any other * command. * - *

The default command for every claimable resource is an idle command. + *

The {@link #getDefaultCommand() default command} for every mechanism is an idle command + * unless a different default command has been configured. * * @return A new idle command. */ @@ -123,9 +134,9 @@ public Command idle() { } /** - * Returns a command that idles this resource for the given duration of time. + * Returns a command that idles this mechanism for the given duration of time. * - * @param duration How long the resource should idle for. + * @param duration How long the mechanism should idle for. * @return A new idle command. */ public Command idle(Time duration) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 28a6935433a..7379172a96b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -20,7 +20,7 @@ public class ParallelGroup implements Command { private final Collection m_commands = new LinkedHashSet<>(); private final Collection m_requiredCommands = new HashSet<>(); - private final Set m_requirements = new HashSet<>(); + private final Set m_requirements = new HashSet<>(); private final String m_name; private final int m_priority; @@ -60,7 +60,7 @@ public ParallelGroup( } if (c1.conflictsWith(c2)) { throw new IllegalArgumentException( - "Commands in a parallel composition cannot require the same resources. " + "Commands in a parallel composition cannot require the same mechanisms. " + c1.name() + " and " + c2.name() @@ -93,7 +93,7 @@ public static ParallelGroupBuilder race(Command... commands) { /** * Creates a parallel group that runs all the given commands until they all finish. If a command - * finishes early, its required resources will be idle (uncommanded) until the group completes. + * finishes early, its required mechanisms will be idle (uncommanded) until the group completes. * * @param commands the commands to run in parallel * @return the group @@ -123,7 +123,7 @@ public String name() { } @Override - public Set requirements() { + public Set requirements() { return m_requirements; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 980ea9ea891..60c062237ad 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -90,7 +90,7 @@ * protobuf serializer. However, it is up to the user to log those events themselves. */ public class Scheduler implements ProtobufSerializable { - private final Map m_defaultCommands = new LinkedHashMap<>(); + private final Map m_defaultCommands = new LinkedHashMap<>(); /** The set of commands scheduled since the start of the previous run. */ private final Set m_onDeck = new LinkedHashSet<>(); @@ -125,8 +125,8 @@ public class Scheduler implements ProtobufSerializable { /** * Gets the default scheduler instance for use in a robot program. Unless otherwise specified, - * triggers and resources will be registered with the default scheduler and require the default - * scheduler to run. However, triggers and resources can be constructed to be registered with a + * triggers and mechanisms will be registered with the default scheduler and require the default + * scheduler to run. However, triggers and mechanisms can be constructed to be registered with a * specific scheduler instance, which may be useful for isolation for unit tests. * * @return the default scheduler instance. @@ -138,41 +138,41 @@ public static Scheduler getDefault() { public Scheduler() {} /** - * Sets the default command for a resource. The command must require that resource, and cannot - * require any other resources. + * Sets the default command for a mechanism. The command must require that mechanism, and cannot + * require any other mechanisms. * - * @param resource the resource for which to set the default command - * @param defaultCommand the default command to execute on the resource + * @param mechanism the mechanism for which to set the default command + * @param defaultCommand the default command to execute on the mechanism * @throws IllegalArgumentException if the command does not meet the requirements for being a * default command */ - public void scheduleAsDefaultCommand(RequireableResource resource, Command defaultCommand) { - if (!defaultCommand.requires(resource)) { - throw new IllegalArgumentException("A resource's default command must require that resource"); + public void scheduleAsDefaultCommand(Mechanism mechanism, Command defaultCommand) { + if (!defaultCommand.requires(mechanism)) { + throw new IllegalArgumentException("A mechanism's default command must require that mechanism"); } if (defaultCommand.requirements().size() > 1) { throw new IllegalArgumentException( - "A resource's default command cannot require other resources"); + "A mechanism's default command cannot require other mechanisms"); } - m_defaultCommands.put(resource, defaultCommand); + m_defaultCommands.put(mechanism, defaultCommand); schedule(defaultCommand); } /** - * Gets the default command set for a resource. + * Gets the default command set for a mechanism. * - * @param resource The resource + * @param mechanism The mechanism * @return The default command, or null if no default command was ever set */ - public Command getDefaultCommandFor(RequireableResource resource) { - return m_defaultCommands.get(resource); + public Command getDefaultCommandFor(Mechanism mechanism) { + return m_defaultCommands.get(mechanism); } /** * Adds a callback to run as part of the scheduler. The callback should not manipulate or control - * any resources, but can be used to log information, update data (such as simulations or LED data + * any mechanisms, but can be used to log information, update data (such as simulations or LED data * buffers), or perform some other helpful task. The callback is responsible for managing its own * control flow and end conditions. If you want to run a single task periodically for the entire * lifespan of the scheduler, use {@link #addPeriodic(Runnable)}. @@ -235,7 +235,7 @@ public enum ScheduleResult { * would be enough to delay actions by 100 milliseconds - instead of only 20. * *

Does nothing if the command is already scheduled or running, or requires at least one - * resource already used by a higher priority command. + * mechanism already used by a higher priority command. * *

If one command schedules another ("parent" and "fork"), the forked command will be canceled * when the parent command completes. It is not possible to fork a command and have it live longer @@ -243,7 +243,7 @@ public enum ScheduleResult { * * @param command the command to schedule * @throws IllegalArgumentException if scheduled by a command composition that has already - * scheduled another command that shares at least one required resource + * scheduled another command that shares at least one required mechanism */ public ScheduleResult schedule(Command command) { // Note: we use a throwable here instead of Thread.currentThread().getStackTrace() for easier @@ -274,7 +274,7 @@ ScheduleResult schedule(Binding binding) { } if (command.isLowerPriorityThan(scheduledState.command())) { // Lower priority than an already-scheduled (but not yet running) command that requires at - // one of the same resource. Ignore it. + // one of the same mechanism. Ignore it. return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; } } @@ -431,7 +431,7 @@ public void cancel(Command command) { boolean running = isRunning(command); // Evict the command. The next call to run() will schedule the default command for all its - // required resources, unless another command requiring those resources is scheduled between + // required mechanisms, unless another command requiring those mechanisms is scheduled between // calling cancel() and calling run() m_commandStates.remove(command); m_onDeck.removeIf(state -> state.command() == command); @@ -452,7 +452,7 @@ public void cancel(Command command) { * {@link #getDefaultEventLoop() default event loop}, begin running any commands scheduled since * the previous call to {@code run()}, process periodic callbacks added with {@link * #addPeriodic(Runnable)} and {@link #sideload(Consumer)}, update running commands, and schedule - * default commands for any resources that are not owned by a running command. + * default commands for any mechanisms that are not owned by a running command. * *

This method is intended to be called in a periodic loop like {@link * TimedRobot#robotPeriodic()} @@ -598,15 +598,15 @@ public Command currentCommand() { } private void scheduleDefaultCommands() { - // Schedule the default commands for every resource that doesn't currently have a running or + // Schedule the default commands for every mechanism that doesn't currently have a running or // scheduled command. m_defaultCommands.forEach( - (resource, defaultCommand) -> { - if (m_commandStates.keySet().stream().noneMatch(c -> c.requires(resource)) - && m_onDeck.stream().noneMatch(c -> c.command().requires(resource)) + (mechanism, defaultCommand) -> { + if (m_commandStates.keySet().stream().noneMatch(c -> c.requires(mechanism)) + && m_onDeck.stream().noneMatch(c -> c.command().requires(mechanism)) && defaultCommand != null) { // Nothing currently running or scheduled - // Schedule the resource's default command, if it has one + // Schedule the mechanism's default command, if it has one schedule(defaultCommand); } }); @@ -679,14 +679,14 @@ public Collection getRunningCommands() { } /** - * Gets all the currently running commands that require a particular resource. Commands are + * Gets all the currently running commands that require a particular mechanism. Commands are * returned in the order in which they were scheduled. The returned list is read-only. * - * @param resource the resource to get the commands for - * @return the currently running commands that require the resource. + * @param mechanism the mechanism to get the commands for + * @return the currently running commands that require the mechanism. */ - public List getRunningCommandsFor(RequireableResource resource) { - return m_commandStates.keySet().stream().filter(command -> command.requires(resource)).toList(); + public List getRunningCommandsFor(Mechanism mechanism) { + return m_commandStates.keySet().stream().filter(command -> command.requires(mechanism)).toList(); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index a9cac2e55b4..151ff3805bf 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -96,10 +96,10 @@ record CompletedWithError(Command command, Throwable error, long timestampMicros /** * An event marking when a command was evicted from the scheduler. Commands may be evicted when - * they've been scheduled, then another command requiring a shared resource is scheduled + * they've been scheduled, then another command requiring a shared mechanism is scheduled * afterward; when cancelled via {@link Scheduler#cancel(Command)} or {@link * Scheduler#cancelAll()}; or when they're running and interrupted by another command requiring a - * shared resource. + * shared mechanism. * * @param command The command that was evicted * @param timestampMicros When the command was evicted diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index cede996013a..1ae95a01f59 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -15,14 +15,14 @@ * any of its commands. If all commands in the sequence are able to run while the robot is disabled, * then the sequence itself will be allowed to run while the robot is disabled. * - *

The sequence will own all resources required by all commands in the sequence for the - * entire duration of the sequence. This means that a resource owned by one command in the sequence, + *

The sequence will own all mechanisms required by all commands in the sequence for the + * entire duration of the sequence. This means that a mechanism owned by one command in the sequence, * but not by a later one, will be uncommanded while that later command executes. */ public class Sequence implements Command { private final String m_name; private final List m_commands = new ArrayList<>(); - private final Set m_requirements = new HashSet<>(); + private final Set m_requirements = new HashSet<>(); private final int m_priority; /** @@ -56,7 +56,7 @@ public String name() { } @Override - public Set requirements() { + public Set requirements() { return m_requirements; } @@ -91,7 +91,7 @@ public static SequenceBuilder sequence(Command... commands) { /** * Creates a command that executes the given commands in sequence. The returned command will - * require all the resources required by every command in the sequence, and will have a priority + * require all the mechanisms required by every command in the sequence, and will have a priority * equal to the highest priority of all the given commands. * * @param commands The commands to execute in sequence diff --git a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java index 950c3526d36..0445a4b43d8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java @@ -34,7 +34,7 @@ public String name() { } @Override - public Set requirements() { + public Set requirements() { return Set.of(); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index a70b7feaf81..5d48485b04c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -49,8 +49,8 @@ public void pack(ProtobufCommand msg, Command command) { msg.setPriority(command.priority()); for (var requirement : command.requirements()) { - var rrp = new RequireableResourceProto(); - ProtobufRequireableResource requirementMessage = rrp.createMessage(); + var rrp = new MechanismProto(); + ProtobufMechanism requirementMessage = rrp.createMessage(); rrp.pack(requirementMessage, requirement); msg.addRequirements(requirementMessage); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java new file mode 100644 index 00000000000..42236110425 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java @@ -0,0 +1,36 @@ +// 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 org.wpilib.commands3.proto; + +import edu.wpi.first.util.protobuf.Protobuf; +import org.wpilib.commands3.Mechanism; +import us.hebi.quickbuf.Descriptors; + +public class MechanismProto implements Protobuf { + @Override + public Class getTypeClass() { + return Mechanism.class; + } + + @Override + public Descriptors.Descriptor getDescriptor() { + return ProtobufMechanism.getDescriptor(); + } + + @Override + public ProtobufMechanism createMessage() { + return ProtobufMechanism.newInstance(); + } + + @Override + public Mechanism unpack(ProtobufMechanism msg) { + throw new UnsupportedOperationException("Deserialization not supported"); + } + + @Override + public void pack(ProtobufMechanism msg, Mechanism value) { + msg.setName(value.getName()); + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.java deleted file mode 100644 index 4084fca0451..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/RequireableResourceProto.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 org.wpilib.commands3.proto; - -import edu.wpi.first.util.protobuf.Protobuf; -import org.wpilib.commands3.RequireableResource; -import us.hebi.quickbuf.Descriptors; - -public class RequireableResourceProto - implements Protobuf { - @Override - public Class getTypeClass() { - return RequireableResource.class; - } - - @Override - public Descriptors.Descriptor getDescriptor() { - return ProtobufRequireableResource.getDescriptor(); - } - - @Override - public ProtobufRequireableResource createMessage() { - return ProtobufRequireableResource.newInstance(); - } - - @Override - public RequireableResource unpack(ProtobufRequireableResource msg) { - throw new UnsupportedOperationException("Deserialization not supported"); - } - - @Override - public void pack(ProtobufRequireableResource msg, RequireableResource value) { - msg.setName(value.getName()); - } -} diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/scheduler.proto index 6fb8193c3b7..9d9b7d82f41 100644 --- a/commandsv3/src/main/proto/scheduler.proto +++ b/commandsv3/src/main/proto/scheduler.proto @@ -11,7 +11,7 @@ allwpilib $ protoc-quickbuf \ commandsv3/src/main/proto/scheduler.proto */ -message ProtobufRequireableResource { +message ProtobufMechanism { string name = 1; } @@ -30,8 +30,8 @@ message ProtobufCommand { // The priority level of the command. int32 priority = 4; - // The resources required by the command. - repeated ProtobufRequireableResource requirements = 5; + // The mechanisms required by the command. + repeated ProtobufMechanism requirements = 5; // How much time the command took to execute in its most recent run. // Only included in a message for an actively running command. diff --git a/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java b/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java index c3f8429db25..e66060c7d45 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/NullCommand.java @@ -18,7 +18,7 @@ public String name() { } @Override - public Set requirements() { + public Set requirements() { return Set.of(); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index dfddcbbfb08..2d112400013 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -23,8 +23,8 @@ void setup() { @Test void parallelAll() { - var r1 = new RequireableResource("R1", m_scheduler); - var r2 = new RequireableResource("R2", m_scheduler); + var r1 = new Mechanism("R1", m_scheduler); + var r2 = new Mechanism("R2", m_scheduler); var c1Count = new AtomicInteger(0); var c2Count = new AtomicInteger(0); @@ -89,8 +89,8 @@ void parallelAll() { @Test void race() { - var r1 = new RequireableResource("R1", m_scheduler); - var r2 = new RequireableResource("R2", m_scheduler); + var r1 = new Mechanism("R1", m_scheduler); + var r2 = new Mechanism("R2", m_scheduler); var c1Count = new AtomicInteger(0); var c2Count = new AtomicInteger(0); @@ -146,12 +146,12 @@ void race() { @Test void nested() { - var resource = new RequireableResource("Resource", m_scheduler); + var mechanism = new Mechanism("mechanism", m_scheduler); var count = new AtomicInteger(0); var command = - resource + mechanism .run( coroutine -> { for (int i = 0; i < 5; i++) { diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index ff5ab179f16..cfe74635908 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -63,7 +63,7 @@ void basic() { @Test void higherPriorityCancels() { - final var subsystem = new RequireableResource("Subsystem", m_scheduler); + final var subsystem = new Mechanism("Subsystem", m_scheduler); final var lower = new PriorityCommand(-1000, subsystem); final var higher = new PriorityCommand(+1000, subsystem); @@ -80,7 +80,7 @@ void higherPriorityCancels() { @Test void lowerPriorityDoesNotCancel() { - final var subsystem = new RequireableResource("Subsystem", m_scheduler); + final var subsystem = new Mechanism("Subsystem", m_scheduler); final var lower = new PriorityCommand(-1000, subsystem); final var higher = new PriorityCommand(+1000, subsystem); @@ -101,7 +101,7 @@ void lowerPriorityDoesNotCancel() { @Test void samePriorityCancels() { - final var subsystem = new RequireableResource("Subsystem", m_scheduler); + final var subsystem = new Mechanism("Subsystem", m_scheduler); final var first = new PriorityCommand(512, subsystem); final var second = new PriorityCommand(512, subsystem); @@ -119,8 +119,8 @@ void samePriorityCancels() { @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void atomicity() { - var resource = - new RequireableResource("X", m_scheduler) { + var mechanism = + new Mechanism("X", m_scheduler) { int m_x = 0; }; @@ -137,7 +137,7 @@ void atomicity() { coroutine -> { for (int i = 0; i < iterations; i++) { coroutine.yield(); - resource.m_x++; + mechanism.m_x++; } }) .named("CountCommand[" + cmdCount + "]"); @@ -150,16 +150,16 @@ void atomicity() { } m_scheduler.run(); - assertEquals(numCommands * iterations, resource.m_x); + assertEquals(numCommands * iterations, mechanism.m_x); } @Test @SuppressWarnings("PMD.AvoidCatchingGenericException") void errorDetection() { - var resource = new RequireableResource("X", m_scheduler); + var mechanism = new Mechanism("X", m_scheduler); var command = - resource + mechanism .run( coroutine -> { throw new RuntimeException("The exception"); @@ -244,9 +244,9 @@ void nestedErrorDetection() { @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs - void runResource() { + void runmechanism() { var example = - new RequireableResource("Counting", m_scheduler) { + new Mechanism("Counting", m_scheduler) { int m_x = 0; }; @@ -275,13 +275,13 @@ void runResource() { void cancelOnInterruptDoesNotResume() { var count = new AtomicInteger(0); - var resource = new RequireableResource("Resource", m_scheduler); + var mechanism = new Mechanism("mechanism", m_scheduler); var interrupter = - Command.requiring(resource).executing(coroutine -> {}).withPriority(2).named("Interrupter"); + Command.requiring(mechanism).executing(coroutine -> {}).withPriority(2).named("Interrupter"); var canceledCommand = - Command.requiring(resource) + Command.requiring(mechanism) .executing( coroutine -> { count.set(1); @@ -303,9 +303,9 @@ void cancelOnInterruptDoesNotResume() { void scheduleOverDefaultDoesNotRescheduleDefault() { var count = new AtomicInteger(0); - var resource = new RequireableResource("Resource", m_scheduler); + var mechanism = new Mechanism("mechanism", m_scheduler); var defaultCmd = - resource + mechanism .run( coroutine -> { while (true) { @@ -316,8 +316,8 @@ void scheduleOverDefaultDoesNotRescheduleDefault() { .withPriority(-1) .named("Default Command"); - final var newerCmd = resource.run(coroutine -> {}).named("Newer Command"); - resource.setDefaultCommand(defaultCmd); + final var newerCmd = mechanism.run(coroutine -> {}).named("Newer Command"); + mechanism.setDefaultCommand(defaultCmd); m_scheduler.run(); assertTrue(m_scheduler.isRunning(defaultCmd), "Default command should be running"); @@ -364,13 +364,13 @@ void cancelAllCancelsAll() { @Test void cancelAllStartsDefaults() { - var resources = new ArrayList(10); + var mechanisms = new ArrayList(10); for (int i = 1; i <= 10; i++) { - resources.add(new RequireableResource("System " + i, m_scheduler)); + mechanisms.add(new Mechanism("System " + i, m_scheduler)); } var command = - new CommandBuilder().requiring(resources).executing(Coroutine::yield).named("Big Command"); + new CommandBuilder().requiring(mechanisms).executing(Coroutine::yield).named("Big Command"); // Scheduling the command should evict the on-deck default commands m_scheduler.schedule(command); @@ -392,16 +392,16 @@ void cancelAllStartsDefaults() { fail(command.name() + " was not canceled by cancelAll()"); } - for (var resource : resources) { - var runningCommands = m_scheduler.getRunningCommandsFor(resource); + for (var mechanism : mechanisms) { + var runningCommands = m_scheduler.getRunningCommandsFor(mechanism); assertEquals( 1, runningCommands.size(), - "Resource " + resource + " should have exactly one running command"); + "mechanism " + mechanism + " should have exactly one running command"); assertInstanceOf( IdleCommand.class, runningCommands.getFirst(), - "Resource " + resource + " is not running the default command"); + "mechanism " + mechanism + " is not running the default command"); } } @@ -437,17 +437,17 @@ void cancelDeeplyNestedCompositions() { @Test void compositionsDoNotSelfCancel() { - var res = new RequireableResource("The Resource", m_scheduler); + var mech = new Mechanism("The mechanism", m_scheduler); var group = - res.run( + mech.run( co -> { co.await( - res.run( + mech.run( co2 -> { co2.await( - res.run( + mech.run( co3 -> { - co3.await(res.run(Coroutine::park).named("Park")); + co3.await(mech.run(Coroutine::park).named("Park")); }) .named("C3")); }) @@ -463,12 +463,12 @@ void compositionsDoNotSelfCancel() { @Test void compositionsDoNotCancelParent() { - var res = new RequireableResource("The Resource", m_scheduler); + var mech = new Mechanism("The mechanism", m_scheduler); var group = - res.run( + mech.run( co -> { - co.fork(res.run(Coroutine::park).named("First Child")); - co.fork(res.run(Coroutine::park).named("Second Child")); + co.fork(mech.run(Coroutine::park).named("First Child")); + co.fork(mech.run(Coroutine::park).named("Second Child")); co.park(); }) .named("Group"); @@ -484,35 +484,35 @@ void compositionsDoNotCancelParent() { @Test void compositionsDoNotNeedRequirements() { - var r1 = new RequireableResource("R1", m_scheduler); - var r2 = new RequireableResource("r2", m_scheduler); + var m1 = new Mechanism("M1", m_scheduler); + var m2 = new Mechanism("m2", m_scheduler); // the group has no requirements, but can schedule child commands that do var group = Command.noRequirements( co -> { co.awaitAll( - r1.run(Coroutine::park).named("R1 Command"), - r2.run(Coroutine::park).named("R2 Command")); + m1.run(Coroutine::park).named("M1 Command"), + m2.run(Coroutine::park).named("M2 Command")); }) .named("Composition"); m_scheduler.schedule(group); - m_scheduler.run(); // start r1 and r2 commands + m_scheduler.run(); // start m1 and m2 commands assertEquals(3, m_scheduler.getRunningCommands().size()); } @Test @SuppressWarnings("PMD.AvoidCatchingGenericException") void compositionsCannotAwaitConflictingCommands() { - var res = new RequireableResource("The Resource", m_scheduler); + var mech = new Mechanism("The mechanism", m_scheduler); var group = Command.noRequirements( co -> { co.awaitAll( - res.run(Coroutine::park).named("First"), - res.run(Coroutine::park).named("Second")); + mech.run(Coroutine::park).named("First"), + mech.run(Coroutine::park).named("Second")); }) .named("Group"); @@ -524,8 +524,8 @@ void compositionsCannotAwaitConflictingCommands() { fail("An exception should have been thrown"); } catch (IllegalArgumentException iae) { assertEquals( - "Command Second requires resources that are already used by First. " - + "Both require The Resource", + "Command Second requires mechanisms that are already used by First. " + + "Both require The mechanism", iae.getMessage()); } catch (Exception e) { fail("Unexpected exception: " + e); @@ -536,9 +536,9 @@ void compositionsCannotAwaitConflictingCommands() { void doesNotRunOnCancelWhenInterruptingOnDeck() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - var interrupter = resource.run(Coroutine::yield).named("Interrupter"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = mechanism.run(Coroutine::yield).named("Interrupter"); m_scheduler.schedule(cmd); m_scheduler.schedule(interrupter); m_scheduler.run(); @@ -550,8 +550,8 @@ void doesNotRunOnCancelWhenInterruptingOnDeck() { void doesNotRunOnCancelWhenCancellingOnDeck() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); m_scheduler.schedule(cmd); // cancelling before calling .run() m_scheduler.cancel(cmd); @@ -564,9 +564,9 @@ void doesNotRunOnCancelWhenCancellingOnDeck() { void runsOnCancelWhenInterruptingCommand() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); - var interrupter = resource.run(Coroutine::park).named("Interrupter"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = mechanism.run(Coroutine::park).named("Interrupter"); m_scheduler.schedule(cmd); m_scheduler.run(); m_scheduler.schedule(interrupter); @@ -579,8 +579,8 @@ void runsOnCancelWhenInterruptingCommand() { void doesNotRunOnCancelWhenCompleting() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); m_scheduler.schedule(cmd); m_scheduler.run(); m_scheduler.run(); @@ -593,8 +593,8 @@ void doesNotRunOnCancelWhenCompleting() { void runsOnCancelWhenCancelling() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); m_scheduler.schedule(cmd); m_scheduler.run(); m_scheduler.cancel(cmd); @@ -606,8 +606,8 @@ void runsOnCancelWhenCancelling() { void runsOnCancelWhenCancellingParent() { var ran = new AtomicBoolean(false); - var resource = new RequireableResource("The Resource", m_scheduler); - var cmd = resource.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); var group = new Sequence("Seq", Collections.singletonList(cmd)); m_scheduler.schedule(group); @@ -630,12 +630,12 @@ void sideloadThrowingException() { } @Test - void nestedResources() { + void nestedmechanisms() { var superstructure = - new RequireableResource("Superstructure", m_scheduler) { - private final RequireableResource m_elevator = - new RequireableResource("Elevator", m_scheduler); - private final RequireableResource m_arm = new RequireableResource("Arm", m_scheduler); + new Mechanism("Superstructure", m_scheduler) { + private final Mechanism m_elevator = + new Mechanism("Elevator", m_scheduler); + private final Mechanism m_arm = new Mechanism("Arm", m_scheduler); public Command superCommand() { return run(co -> { @@ -653,7 +653,7 @@ public Command superCommand() { superstructure.m_arm.getRunningCommands(), "Arm should only be running its default command"); - // Scheduling something that requires an in-use inner resource cancels the outer command + // Scheduling something that requires an in-use inner mechanism cancels the outer command m_scheduler.schedule(superstructure.m_elevator.run(Coroutine::park).named("Conflict")); m_scheduler.run(); // schedules the default superstructure command @@ -663,11 +663,11 @@ public Command superCommand() { @Test void protobuf() { - var res = new RequireableResource("The Resource", m_scheduler); - var parkCommand = res.run(Coroutine::park).named("Park"); - var c3Command = res.run(co -> co.await(parkCommand)).named("C3"); - var c2Command = res.run(co -> co.await(c3Command)).named("C2"); - var group = res.run(co -> co.await(c2Command)).named("Group"); + var mech = new Mechanism("The mechanism", m_scheduler); + var parkCommand = mech.run(Coroutine::park).named("Park"); + var c3Command = mech.run(co -> co.await(parkCommand)).named("C3"); + var c2Command = mech.run(co -> co.await(c3Command)).named("C2"); + var group = mech.run(co -> co.await(c2Command)).named("Group"); m_scheduler.schedule(group); m_scheduler.run(); @@ -700,7 +700,7 @@ void protobuf() { "id": %s, "name": "Group", "requirements": [{ - "name": "The Resource" + "name": "The mechanism" }] }, { "lastTimeMs": %s, @@ -710,7 +710,7 @@ void protobuf() { "parentId": %s, "name": "C2", "requirements": [{ - "name": "The Resource" + "name": "The mechanism" }] }, { "lastTimeMs": %s, @@ -720,7 +720,7 @@ void protobuf() { "parentId": %s, "name": "C3", "requirements": [{ - "name": "The Resource" + "name": "The mechanism" }] }, { "lastTimeMs": %s, @@ -730,7 +730,7 @@ void protobuf() { "parentId": %s, "name": "Park", "requirements": [{ - "name": "The Resource" + "name": "The mechanism" }] }] }""" @@ -766,12 +766,12 @@ void protobuf() { @Test void siblingsInCompositionCanShareRequirements() { - var resource = new RequireableResource("The Resource", m_scheduler); + var mechanism = new Mechanism("The mechanism", m_scheduler); var firstRan = new AtomicBoolean(false); var secondRan = new AtomicBoolean(false); var first = - resource + mechanism .run( c -> { firstRan.set(true); @@ -780,7 +780,7 @@ void siblingsInCompositionCanShareRequirements() { .named("First"); var second = - resource + mechanism .run( c -> { secondRan.set(true); @@ -844,12 +844,12 @@ void nestedOneShotCompositionsAllRunInOneCycle() { @Test void childConflictsWithHigherPriorityTopLevel() { - var resource = new RequireableResource("Resource", m_scheduler); - var top = resource.run(Coroutine::park).withPriority(10).named("Top"); + var mechanism = new Mechanism("mechanism", m_scheduler); + var top = mechanism.run(Coroutine::park).withPriority(10).named("Top"); // Child conflicts with and is lower priority than the Top command // It should not be scheduled, and the parent command should exit immediately - var child = resource.run(Coroutine::park).named("Child"); + var child = mechanism.run(Coroutine::park).named("Child"); var parent = Command.noRequirements(co -> co.await(child)).named("Parent"); m_scheduler.schedule(top); @@ -863,12 +863,12 @@ void childConflictsWithHigherPriorityTopLevel() { @Test void childConflictsWithLowerPriorityTopLevel() { - var resource = new RequireableResource("Resource", m_scheduler); - var top = resource.run(Coroutine::park).withPriority(-10).named("Top"); + var mechanism = new Mechanism("mechanism", m_scheduler); + var top = mechanism.run(Coroutine::park).withPriority(-10).named("Top"); // Child conflicts with and is lower priority than the Top command // It should not be scheduled, and the parent command should exit immediately - var child = resource.run(Coroutine::park).named("Child"); + var child = mechanism.run(Coroutine::park).named("Child"); var parent = Command.noRequirements(co -> co.await(child)).named("Parent"); m_scheduler.schedule(top); @@ -929,14 +929,14 @@ void commandDeadlock() { assertFalse(m_scheduler.isRunning(command2)); } - record PriorityCommand(int priority, RequireableResource... subsystems) implements Command { + record PriorityCommand(int priority, Mechanism... subsystems) implements Command { @Override public void run(Coroutine coroutine) { coroutine.park(); } @Override - public Set requirements() { + public Set requirements() { return Set.of(subsystems); } From 4bc397077094edaa04d30f55574aba7188f7141c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 19:00:29 -0400 Subject: [PATCH 087/153] Rename "generate_hids" to "generate_files" Since it generates HID files and protobuf files, the name was undescriptive --- .github/actions/pregen/action.yml | 5 +++++ commandsv3/BUILD.bazel | 4 ++-- commandsv3/generate.bzl | 2 +- commandsv3/{generate_hids.py => generate_files.py} | 0 4 files changed, 8 insertions(+), 3 deletions(-) rename commandsv3/{generate_hids.py => generate_files.py} (100%) diff --git a/.github/actions/pregen/action.yml b/.github/actions/pregen/action.yml index 1346a796964..844294818e2 100644 --- a/.github/actions/pregen/action.yml +++ b/.github/actions/pregen/action.yml @@ -53,6 +53,11 @@ runs: ./wpimath/generate_quickbuf.py --quickbuf_plugin protoc-gen-quickbuf-1.3.3-linux-x86_64.exe shell: bash + - name: Regenerate Commands v3 + run: | + ./commandsv3/generate_hids.py --quickbuf_plugin protoc-gen-quickbuf-1.3.3-linux-x86_64.exe + shell: bash + - name: Regenerate wpiunits run: ./wpiunits/generate_units.py shell: bash diff --git a/commandsv3/BUILD.bazel b/commandsv3/BUILD.bazel index 40e69d30934..ed5b5a0062a 100644 --- a/commandsv3/BUILD.bazel +++ b/commandsv3/BUILD.bazel @@ -6,8 +6,8 @@ load("//commandsv3:generate.bzl", "generate_commandsv3") load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test", "wpilib_java_library") py_binary( - name = "generate_hids", - srcs = ["generate_hids.py"], + name = "generate_files", + srcs = ["generate_files.py"], target_compatible_with = select({ "@rules_bzlmodrio_toolchains//constraints/is_systemcore:systemcore": ["@platforms//:incompatible"], "//conditions:default": [], diff --git a/commandsv3/generate.bzl b/commandsv3/generate.bzl index 34b81ab54b8..4c462cc3419 100644 --- a/commandsv3/generate.bzl +++ b/commandsv3/generate.bzl @@ -37,7 +37,7 @@ generate_commandsv3 = rule( default = Label("//commandsv3:templates"), ), "_tool": attr.label( - default = Label("//commandsv3:generate_hids"), + default = Label("//commandsv3:generate_files"), cfg = "exec", executable = True, ), diff --git a/commandsv3/generate_hids.py b/commandsv3/generate_files.py similarity index 100% rename from commandsv3/generate_hids.py rename to commandsv3/generate_files.py From db2c85c360cacf603adb7f0ccfd1d592f43a08e7 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 19:02:45 -0400 Subject: [PATCH 088/153] Update design doc with new name --- design-docs/commands-v3.md | 56 +++++++++++++++++++------------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 8cb40b12876..9c46988bfaf 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -55,12 +55,12 @@ required in order for commands to be constructed. See [Telemetry](#telemetry) fo ### Uncommanded Behavior Command groups - or, more generally, commands that schedule other commands - need to own all -resources needed by all their inner commands. However, if they don’t *directly* control a resource, -then they will still own the resource whenever they’re not running an inner command that uses it, -causing the resource to be in an *uncommanded state*. This can cause unexpected behavior with +mechanisms needed by all their inner commands. However, if they don’t *directly* control a mechanism, +then they will still own the mechanism whenever they’re not running an inner command that uses it, +causing the mechanism to be in an *uncommanded state*. This can cause unexpected behavior with parallel groups where inner commands don’t all end at the same time, and especially with sequential groups. For example, something as seemingly basic as `elevator.toL4().andThen(coral.score())` would -*own* the elevator and coral resources for the entire sequence, but not control the elevator during +*own* the elevator and coral mechanisms for the entire sequence, but not control the elevator during the coral scoring section, nor control the coral scoring mechanism while the elevator is moving. The v2 framework worked around this problem with so-called proxy commands, which have no @@ -70,27 +70,27 @@ command to run after the proxied command completed. It also meant that *every* c that subsystem would also need to be proxied; otherwise, the group would still have ownership of the subsystem, and the proxied command would interrupt it (and thus itself). -The v3 framework allows nested commands to use resources not required by the parent command; -however, the built-in parallel and sequential groups will take full ownership of all resources +The v3 framework allows nested commands to use mechanisms not required by the parent command; +however, the built-in parallel and sequential groups will take full ownership of all mechanisms required by their nested commands for safety and to keep behavior parity with previous command frameworks. ```java public Command outerCommand() { - // The outer command only requires the outer resource + // The outer command only requires the outer mechanism return run(coroutine -> { - // But can schedule a command that requires any other resource - coroutine.await(innerResource.innerCommand()); - // And only requires that inner resource while its command runs - coroutine.await(otherResource().otherCommand()); + // But can schedule a command that requires any other mechanism + coroutine.await(innerMechanism.innerCommand()); + // And only requires that inner mechanism while its command runs + coroutine.await(otherMechanism().otherCommand()); }).named("Outer"); } ``` -Scheduling a command that requires an inner resource will also cancel its parent, even if the parent -does not require that inner resource. Using the above example, directly scheduling a command that -requires `innerResource` will cancel a running `outerCommand` - but only if `outerCommand` is -*currently using* the inner resource at the time. +Scheduling a command that requires an inner mechanism will also cancel its parent, even if the parent +does not require that inner mechanism. Using the above example, directly scheduling a command that +requires `innerMechanism` will cancel a running `outerCommand` - but only if `outerCommand` is +*currently using* the inner mechanism at the time. **Effectively, all child commands in v3 are "proxied"**, using the v2 framework's definition, unless using the built-in ParallelGroup and Sequence compositions or explicitly adding child command @@ -162,7 +162,7 @@ scheduler and do not appear in its sendable implementation, making telemetry dif groups will automatically include the names of all their constituent commands, with options to override when desired. -The v3 framework will also provide a map of what command each resource is owned by. The v2 framework +The v3 framework will also provide a map of what command each mechanism is owned by. The v2 framework only provides a list of the names of the running commands, without mapping those to subsystems. This also makes telemetry difficult, since the order of commands in the list does not correspond with subsystems; a command at a particular index may require different subsystems than a different @@ -171,7 +171,7 @@ AdvantageScope difficult since we can’t rely on consistent ordering. Telemetry will send lists of the on-deck and running commands. Commands in those lists will appear as an ID number, parent command ID (if any; top level commands have no parent), name, names of -the required resources, priority level, last time to process, and total processing time. Separate +the required mechanisms, priority level, last time to process, and total processing time. Separate runs of the same command object have different ID numbers and processing time data. The total time spent in the scheduler loop will also be included, but not the aggregate total of _all_ loops. @@ -232,7 +232,7 @@ running will be removed from the queue of scheduled commands. Cancellation reque the end of each `run() `invocation. Cancelled commands are unmounted and will not be re-mounted; they must be rescheduled and be issued new carrier coroutines. -**Interrupt**: Scheduling a command that requires one or more resources already in use by a running +**Interrupt**: Scheduling a command that requires one or more mechanisms already in use by a running command will interrupt and cancel that running command, so long as the running command has an equal or lower priority level. Higher-priority commands cannot be interrupted by lower-priority ones. @@ -350,7 +350,7 @@ caused by loop timings for deeply nested commands. ### Interruption -* Caused by scheduling a command that requires resources already in use by one or more running +* Caused by scheduling a command that requires mechanisms already in use by one or more running commands * Results in cancellation of the conflicting commands * Commands are moved to a pending-cancellation state @@ -365,7 +365,7 @@ caused by loop timings for deeply nested commands. Scheduler state is serialized using protobuf. The scheduler will send a list of the currently queued commands and a list of the current running commands. Commands are serialized as (id: uint32, -parent_id: uint32, name: string, priority: int32, required_resources: string array, +parent_id: uint32, name: string, priority: int32, requirements: string array, last_time_ms: double, total_time_ms: double). Consumers can use the `id` and `parent_id` attributes to reconstruct the tree structure, if desired. `id` and `parent_id` marginally increase the size of serialized data, but make the schema and deserialization quite simple. @@ -380,20 +380,20 @@ will always appear _after_ their parent. For example, if a scheduler is running a command like this: ```java -RequireableResource r1, r2; +Mechansism m1, m2; Command theCommand() { return ParallelGroup.all( - r1.run(/* ... */).withPriority(1).named("Command 1"), - r2.run(/* ... */).withPriority(2).named("Command 2") + m1.run(/* ... */).withPriority(1).named("Command 1"), + m2.run(/* ... */).withPriority(2).named("Command 2") ).withAutomaticName(); } ``` Telemetry for commands in the scheduler would look like: -| `id` | `parent_id` | `name` | `priority` | `required_resources` | `last_time_ms` | `total_time_ms` | -|--------|-------------|---------------------------|------------|----------------------|----------------|-----------------| -| 347123 | -- | "(Command 1 & Command 2)" | 2 | ["R1", "R2"] | 0.210 | 5.122 | -| 998712 | 347123 | "Command 1" | 1 | ["R1"] | 0.051 | 1.241 | -| 591564 | 347123 | "Command 2" | 2 | ["R2"] | 0.108 | 3.249 | +| `id` | `parent_id` | `name` | `priority` | `requirements` | `last_time_ms` | `total_time_ms` | +|--------|-------------|---------------------------|------------|----------------|----------------|-----------------| +| 347123 | -- | "(Command 1 & Command 2)" | 2 | ["M1", "M2"] | 0.210 | 5.122 | +| 998712 | 347123 | "Command 1" | 1 | ["M1"] | 0.051 | 1.241 | +| 591564 | 347123 | "Command 2" | 2 | ["M2"] | 0.108 | 3.249 | From ae6d01bd8d2e3abe4b53e95897b2c264b05eeb0b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 19:17:15 -0400 Subject: [PATCH 089/153] Update script name in comment and github action --- .github/actions/pregen/action.yml | 2 +- commandsv3/src/generate/main/java/commandhid.java.jinja | 2 +- .../java/org/wpilib/commands3/button/CommandPS4Controller.java | 2 +- .../java/org/wpilib/commands3/button/CommandPS5Controller.java | 2 +- .../org/wpilib/commands3/button/CommandStadiaController.java | 2 +- .../java/org/wpilib/commands3/button/CommandXboxController.java | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/actions/pregen/action.yml b/.github/actions/pregen/action.yml index 844294818e2..e05e19e1ba6 100644 --- a/.github/actions/pregen/action.yml +++ b/.github/actions/pregen/action.yml @@ -55,7 +55,7 @@ runs: - name: Regenerate Commands v3 run: | - ./commandsv3/generate_hids.py --quickbuf_plugin protoc-gen-quickbuf-1.3.3-linux-x86_64.exe + ./commandsv3/generate_files.py --quickbuf_plugin protoc-gen-quickbuf-1.3.3-linux-x86_64.exe shell: bash - name: Regenerate wpiunits diff --git a/commandsv3/src/generate/main/java/commandhid.java.jinja b/commandsv3/src/generate/main/java/commandhid.java.jinja index 65ee942de41..3ec45e4b2aa 100644 --- a/commandsv3/src/generate/main/java/commandhid.java.jinja +++ b/commandsv3/src/generate/main/java/commandhid.java.jinja @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_files.py. DO NOT MODIFY {% macro capitalize_first(string) -%} {{ string[0]|capitalize + string[1:] }} {%- endmacro %} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index 31272424867..1e7f15f2ea2 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_files.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 6baf2f72b8c..92f5ef4fba2 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_files.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java index 26ac1f8f62e..c04ae972994 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_files.py. DO NOT MODIFY package org.wpilib.commands3.button; diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java index 65f3aba7ed2..9ad482df539 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -2,7 +2,7 @@ // 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. -// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_hids.py. DO NOT MODIFY +// THIS FILE WAS AUTO-GENERATED BY ./commandsv3/generate_files.py. DO NOT MODIFY package org.wpilib.commands3.button; From 56393c4108b75b78b008fbf56f6dc6a774f4dabb Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 19:18:32 -0400 Subject: [PATCH 090/153] Linting --- .../java/org/wpilib/commands3/Command.java | 31 +++++++++---------- .../org/wpilib/commands3/IdleCommand.java | 6 ++-- .../java/org/wpilib/commands3/Mechanism.java | 6 ++-- .../java/org/wpilib/commands3/Scheduler.java | 15 +++++---- .../java/org/wpilib/commands3/Sequence.java | 4 +-- .../org/wpilib/commands3/SchedulerTest.java | 8 +++-- 6 files changed, 37 insertions(+), 33 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 12d2455d840..eb77ff6d94b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -11,11 +11,11 @@ import java.util.function.Consumer; /** - * Performs some task using one or more {@link Mechanism resources} using the - * collaborative concurrency tools added in Java 21; namely, continuations. Continuations allow - * commands to be executed concurrently in a collaborative manner as coroutines; instead of needing - * to split command behavior into distinct functions (initialize(), execute(), end(), and - * isFinished()), commands can be implemented with a single, imperative loop. + * Performs some task using one or more {@link Mechanism resources} using the collaborative + * concurrency tools added in Java 21; namely, continuations. Continuations allow commands to be + * executed concurrently in a collaborative manner as coroutines; instead of needing to split + * command behavior into distinct functions (initialize(), execute(), end(), and isFinished()), + * commands can be implemented with a single, imperative loop. * *

Note: Because coroutines are opt-in collaborate constructs, every * command implementation must call {@link Coroutine#yield()} within any periodic @@ -29,15 +29,14 @@ * command with an equal or greater {@link #priority()} is scheduled that requires one or more of * those same resources, it will interrupt and cancel the running command. * - *

The recommended way to create a command is using {@link Mechanism#run(Consumer)} or - * a related factory method to create commands that require a single resource (for example, a - * command that drives an elevator up and down or rotates an arm). Commands may be composed - * into {@link ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex - * behavior out of fundamental building blocks. These built-in compositions will require every - * resource used by every command in them, even if those commands aren't always running, and thus - * can leave certain required resources in an uncommanded state: owned, but not used, this - * can lead to mechanisms sagging under gravity or running the motor control request they were - * given. + *

The recommended way to create a command is using {@link Mechanism#run(Consumer)} or a related + * factory method to create commands that require a single resource (for example, a command that + * drives an elevator up and down or rotates an arm). Commands may be composed into {@link + * ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex behavior out + * of fundamental building blocks. These built-in compositions will require every resource used by + * every command in them, even if those commands aren't always running, and thus can leave certain + * required resources in an uncommanded state: owned, but not used, this can lead to + * mechanisms sagging under gravity or running the motor control request they were given. * *

Advanced Usage

* @@ -167,8 +166,8 @@ default boolean requires(Mechanism mechanism) { * Checks if this command conflicts with another command. * * @param other the commands to check against - * @return true if both commands require at least one of the same mechanism, false if both commands - * have completely different requirements + * @return true if both commands require at least one of the same mechanism, false if both + * commands have completely different requirements */ default boolean conflictsWith(Command other) { return !Collections.disjoint(requirements(), other.requirements()); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java index f3e6c98889c..a16505af9f6 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java @@ -10,9 +10,9 @@ import java.util.Set; /** - * An idle command that owns a mechanism without doing anything. It has the lowest possible priority, - * and can be interrupted by any other command that requires the same mechanism. Cancellation and - * interruption function like a normal command. + * An idle command that owns a mechanism without doing anything. It has the lowest possible + * priority, and can be interrupted by any other command that requires the same mechanism. + * Cancellation and interruption function like a normal command. */ public final class IdleCommand implements Command { private final Mechanism m_mechanism; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index 2585e0c4c90..7d23631561e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -23,9 +23,9 @@ public class Mechanism { private final Scheduler m_registeredScheduler; /** - * Creates a new mechanism registered with the default scheduler instance and named - * using the name of the class. Intended to be used by subclasses to get sane defaults without - * needing to manually declare a constructor. + * Creates a new mechanism registered with the default scheduler instance and named using the name + * of the class. Intended to be used by subclasses to get sane defaults without needing to + * manually declare a constructor. */ @SuppressWarnings("this-escape") protected Mechanism() { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 60c062237ad..0a6a402211b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -148,7 +148,8 @@ public Scheduler() {} */ public void scheduleAsDefaultCommand(Mechanism mechanism, Command defaultCommand) { if (!defaultCommand.requires(mechanism)) { - throw new IllegalArgumentException("A mechanism's default command must require that mechanism"); + throw new IllegalArgumentException( + "A mechanism's default command must require that mechanism"); } if (defaultCommand.requirements().size() > 1) { @@ -172,10 +173,10 @@ public Command getDefaultCommandFor(Mechanism mechanism) { /** * Adds a callback to run as part of the scheduler. The callback should not manipulate or control - * any mechanisms, but can be used to log information, update data (such as simulations or LED data - * buffers), or perform some other helpful task. The callback is responsible for managing its own - * control flow and end conditions. If you want to run a single task periodically for the entire - * lifespan of the scheduler, use {@link #addPeriodic(Runnable)}. + * any mechanisms, but can be used to log information, update data (such as simulations or LED + * data buffers), or perform some other helpful task. The callback is responsible for managing its + * own control flow and end conditions. If you want to run a single task periodically for the + * entire lifespan of the scheduler, use {@link #addPeriodic(Runnable)}. * *

Note: Like commands, any loops in the callback must appropriately yield * control back to the scheduler with {@link Coroutine#yield} or risk stalling your program in an @@ -686,7 +687,9 @@ public Collection getRunningCommands() { * @return the currently running commands that require the mechanism. */ public List getRunningCommandsFor(Mechanism mechanism) { - return m_commandStates.keySet().stream().filter(command -> command.requires(mechanism)).toList(); + return m_commandStates.keySet().stream() + .filter(command -> command.requires(mechanism)) + .toList(); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 1ae95a01f59..3f5d7b97b0e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -16,8 +16,8 @@ * then the sequence itself will be allowed to run while the robot is disabled. * *

The sequence will own all mechanisms required by all commands in the sequence for the - * entire duration of the sequence. This means that a mechanism owned by one command in the sequence, - * but not by a later one, will be uncommanded while that later command executes. + * entire duration of the sequence. This means that a mechanism owned by one command in the + * sequence, but not by a later one, will be uncommanded while that later command executes. */ public class Sequence implements Command { private final String m_name; diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index cfe74635908..4244b17cbb6 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -278,7 +278,10 @@ void cancelOnInterruptDoesNotResume() { var mechanism = new Mechanism("mechanism", m_scheduler); var interrupter = - Command.requiring(mechanism).executing(coroutine -> {}).withPriority(2).named("Interrupter"); + Command.requiring(mechanism) + .executing(coroutine -> {}) + .withPriority(2) + .named("Interrupter"); var canceledCommand = Command.requiring(mechanism) @@ -633,8 +636,7 @@ void sideloadThrowingException() { void nestedmechanisms() { var superstructure = new Mechanism("Superstructure", m_scheduler) { - private final Mechanism m_elevator = - new Mechanism("Elevator", m_scheduler); + private final Mechanism m_elevator = new Mechanism("Elevator", m_scheduler); private final Mechanism m_arm = new Mechanism("Arm", m_scheduler); public Command superCommand() { From 2d667429cd620094699beb9d585bcc30b22fc9b9 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 16 Aug 2025 20:35:21 -0400 Subject: [PATCH 091/153] Cleanup resource -> mechanism rename that wasn't caught earlier A few instances somehow slipped through the first pass --- .../main/java/org/wpilib/commands3/Command.java | 14 +++++++------- .../main/java/org/wpilib/commands3/Scheduler.java | 5 +++-- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index eb77ff6d94b..0b97139e997 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -11,7 +11,7 @@ import java.util.function.Consumer; /** - * Performs some task using one or more {@link Mechanism resources} using the collaborative + * Performs some task using one or more {@link Mechanism mechanisms} using the collaborative * concurrency tools added in Java 21; namely, continuations. Continuations allow commands to be * executed concurrently in a collaborative manner as coroutines; instead of needing to split * command behavior into distinct functions (initialize(), execute(), end(), and isFinished()), @@ -23,19 +23,19 @@ * *

Requirements

* - *

Commands require zero or more resources. To prevent conflicting control requests from running + *

Commands require zero or more mechanisms. To prevent conflicting control requests from running * simultaneously (for example, commanding an elevator to both raise and lower at the same time), a - * running command has exclusive ownership of all of its required resources. If another + * running command has exclusive ownership of all of its required mechanisms. If another * command with an equal or greater {@link #priority()} is scheduled that requires one or more of - * those same resources, it will interrupt and cancel the running command. + * those same mechanisms, it will interrupt and cancel the running command. * *

The recommended way to create a command is using {@link Mechanism#run(Consumer)} or a related - * factory method to create commands that require a single resource (for example, a command that + * factory method to create commands that require a single mechanism (for example, a command that * drives an elevator up and down or rotates an arm). Commands may be composed into {@link * ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex behavior out - * of fundamental building blocks. These built-in compositions will require every resource used by + * of fundamental building blocks. These built-in compositions will require every mechanism used by * every command in them, even if those commands aren't always running, and thus can leave certain - * required resources in an uncommanded state: owned, but not used, this can lead to + * required mechanisms in an uncommanded state: owned, but not used, this can lead to * mechanisms sagging under gravity or running the motor control request they were given. * *

Advanced Usage

diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 0a6a402211b..8cece3ace79 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -70,8 +70,9 @@ * be queued takes precedence over the rest. *
  • Loop over all running commands, mounting and calling each in turn until they either exit or * call {@link Coroutine#yield()}. Commands run in the order in which they were scheduled. - *
  • Queue default commands for any resources without a running command. The queued commands can - * be superseded by any manual scheduling or commands scheduled by triggers in the next run. + *
  • Queue default commands for any mechanisms without a running command. The queued commands + * can be superseded by any manual scheduling or commands scheduled by triggers in the next + * run. * * *

    Telemetry

    From 91c766b2734d85ce0de2dddf3729417242489a94 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 18 Aug 2025 21:41:20 -0400 Subject: [PATCH 092/153] Change artifact name to "commands3" Project name remains "commandsv3" --- commandsv3/BUILD.bazel | 2 +- commandsv3/CommandsV3.json | 2 +- commandsv3/build.gradle | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/commandsv3/BUILD.bazel b/commandsv3/BUILD.bazel index ed5b5a0062a..d7b63f99095 100644 --- a/commandsv3/BUILD.bazel +++ b/commandsv3/BUILD.bazel @@ -44,7 +44,7 @@ filegroup( wpilib_java_library( name = "commandsv3-java", srcs = glob(["src/main/java/**/*.java"]) + [":generated_java"], - maven_artifact_name = "commandsv3-java", + maven_artifact_name = "commands3-java", maven_group_id = "org.wpilib.commands3", visibility = ["//visibility:public"], deps = [ diff --git a/commandsv3/CommandsV3.json b/commandsv3/CommandsV3.json index a941c3ebfb4..72c540ef84f 100644 --- a/commandsv3/CommandsV3.json +++ b/commandsv3/CommandsV3.json @@ -9,7 +9,7 @@ "javaDependencies": [ { "groupId": "org.wpilib.commands3", - "artifactId": "commandsv3-java", + "artifactId": "commands3-java", "version": "wpilib" } ], diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index c5c1b883d78..e5aeca7a217 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -1,10 +1,10 @@ ext { useJava = true useCpp = false - baseId = 'commandsv3' + baseId = 'commands3' groupId = 'org.wpilib' - nativeName = 'commandsv3' + nativeName = 'commands3' devMain = '' } From 9607585c728f53830e6b370eb1a4287d56fa14e9 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 18 Aug 2025 23:27:35 -0400 Subject: [PATCH 093/153] Change command builders to be staged, instead of a single builder object Specifically, this lets us bake required configuration options into the type system, which the previous solution could not do. Effectively, this means that a user forgetting to set the implementation function or name of a command before calling `make()` will be a compile-time error (because `make()` only exists on a builder type that is only accessible once all the required options have been set!) instead of an error at runtime --- .../java/org/wpilib/commands3/Command.java | 28 +- .../wpilib/commands3/CommandTraceHelper.java | 2 +- .../java/org/wpilib/commands3/Coroutine.java | 2 +- .../commands3/HasExecutionCommandBuilder.java | 68 ++++ .../HasRequirementsCommandBuilder.java | 72 +++++ .../java/org/wpilib/commands3/Mechanism.java | 6 +- .../commands3/StagedCommandBuilder.java | 301 ++++++++++++++++++ .../commands3/StartingCommandBuilder.java | 59 ++++ .../commands3/TerminalCommandBuilder.java | 39 +++ .../java/org/wpilib/commands3/Trigger.java | 2 +- .../org/wpilib/commands3/CoroutineTest.java | 26 +- .../wpilib/commands3/ParallelGroupTest.java | 18 +- .../org/wpilib/commands3/SchedulerTest.java | 76 +++-- .../org/wpilib/commands3/SequenceTest.java | 6 +- .../org/wpilib/commands3/TriggerTest.java | 29 +- 15 files changed, 657 insertions(+), 77 deletions(-) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 0b97139e997..f6d9ea8a81e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -5,6 +5,7 @@ package org.wpilib.commands3; import edu.wpi.first.units.measure.Time; +import java.util.Collection; import java.util.Collections; import java.util.Set; import java.util.function.BooleanSupplier; @@ -67,7 +68,7 @@ * // to run when not in use. Interrupting one of the inner commands while it's * // running will cancel the entire sequence. * private Command advancedScoringSequence() { - * return Command.noRequirements(co -> { + * return Command.noRequirements().executing(co -> { * co.await(drivetrain.driveToScoringLocation()); * co.await(elevator.moveToScoringHeight()); * co.await(gripper.release()); @@ -195,11 +196,10 @@ default Command withTimeout(Time timeout) { * resetting odometry and sensors that you don't want to interrupt a command that's controlling * the mechanisms it affects. * - * @param impl the implementation of the command logic * @return a builder that can be used to configure the resulting command */ - static CommandBuilder noRequirements(Consumer impl) { - return new CommandBuilder().executing(impl); + static HasRequirementsCommandBuilder noRequirements() { + return new StagedCommandBuilder().noRequirements(); } /** @@ -209,8 +209,18 @@ static CommandBuilder noRequirements(Consumer impl) { * @param rest Any other required mechanisms * @return A command builder */ - static CommandBuilder requiring(Mechanism requirement, Mechanism... rest) { - return new CommandBuilder().requiring(requirement).requiring(rest); + static HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... rest) { + return new StagedCommandBuilder().requiring(requirement, rest); + } + + /** + * Starts creating a command that requires some number of mechanisms. + * + * @param requirements The required mechanisms. May be empty, but cannot contain null values. + * @return A command builder + */ + static HasRequirementsCommandBuilder requiring(Collection requirements) { + return new StagedCommandBuilder().requiring(requirements); } /** @@ -251,13 +261,13 @@ static SequenceBuilder sequence(Command... commands) { /** * Starts creating a command that simply waits for some condition to be met. The command will * start without any requirements, but some may be added (if necessary) using {@link - * CommandBuilder#requiring(Mechanism)}. + * StagedCommandBuilder#requiring(Mechanism)}. * * @param condition The condition to wait for * @return A command builder */ - static CommandBuilder waitUntil(BooleanSupplier condition) { - return noRequirements(coroutine -> coroutine.waitUntil(condition)); + static HasExecutionCommandBuilder waitUntil(BooleanSupplier condition) { + return noRequirements().executing(coroutine -> coroutine.waitUntil(condition)); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java index 4b0d3b17189..97bcf624761 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandTraceHelper.java @@ -30,7 +30,7 @@ public static StackTraceElement[] modifyTrace( Coroutine.class.getName(), Continuation.class.getName(), Scheduler.class.getName(), - "org.wpilib.commands3.CommandBuilder$1", + "org.wpilib.commands3.StagedCommandBuilder$BuilderBackedCommand", "jdk.internal.vm.Continuation"); boolean sawRun = false; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 920b77a85b9..d4e9ddc1a27 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -87,7 +87,7 @@ public void park() { * *
    {@code
        * Command example() {
    -   *   return Command.noRequirements(coroutine -> {
    +   *   return Command.noRequirements().executing(coroutine -> {
        *     Command inner = ...;
        *     coroutine.fork(inner);
        *     // ... do more things
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    new file mode 100644
    index 00000000000..0cad1c144f1
    --- /dev/null
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    @@ -0,0 +1,68 @@
    +// 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 org.wpilib.commands3;
    +
    +import java.util.function.BooleanSupplier;
    +import java.util.function.Consumer;
    +
    +/**
    + * A stage in a command builder where requirements and main command execution logic have been set.
    + * No more changes to requirements or command implementation may happen after this point. The next
    + * stage is a {@link TerminalCommandBuilder} with {@link #withName(String)}, or straight to a new
    + * command using {@link #named(String)} as shorthand for {@code withName(name).make()}.
    + */
    +public interface HasExecutionCommandBuilder {
    +  /**
    +   * Optionally sets a callback to execute when the command is canceled. The callback will not run
    +   * if the command was canceled after being scheduled but before starting to run, and will not run
    +   * if the command completes naturally or from encountering an unhandled exception.
    +   *
    +   * @param onCancel The function to execute when the command is canceled while running.
    +   * @return This builder object, for chaining
    +   * @throws NullPointerException If {@code onCancel} is null.
    +   */
    +  HasExecutionCommandBuilder whenCanceled(Runnable onCancel);
    +
    +  /**
    +   * Sets the priority level of the command.
    +   *
    +   * @param priority The desired priority level.
    +   * @return This builder object, for chaining.
    +   */
    +  HasExecutionCommandBuilder withPriority(int priority);
    +
    +  /**
    +   * Optionally sets an end condition for the command. If the end condition returns {@code true}
    +   * before the command body set in {@link HasRequirementsCommandBuilder#executing(Consumer)} would
    +   * exit, the command will be cancelled by the scheduler.
    +   *
    +   * @param endCondition An optional end condition for the command. May be null.
    +   * @return This builder object, for chaining.
    +   */
    +  HasExecutionCommandBuilder until(BooleanSupplier endCondition);
    +
    +  /**
    +   * Sets the name of the command. {@link #named(String)} can be used instead if no other
    +   * configuration is necessary after this point.
    +   *
    +   * @param name The name of the command. Cannot be null.
    +   * @return A terminal builder object that can be used to create the command.
    +   * @throws NullPointerException If {@code name} is null.
    +   */
    +  TerminalCommandBuilder withName(String name);
    +
    +  /**
    +   * Creates the command based on the options set during the previous builder stages. The builders
    +   * will no longer be usable after calling this method. Shorthand for {@code
    +   * withName(name).make()}.
    +   *
    +   * @param name The name of the command
    +   * @return The built command.
    +   * @throws NullPointerException If {@code name} is null.
    +   */
    +  default Command named(String name) {
    +    return withName(name).make();
    +  }
    +}
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    new file mode 100644
    index 00000000000..e4d9afa39d0
    --- /dev/null
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    @@ -0,0 +1,72 @@
    +// 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 org.wpilib.commands3;
    +
    +import java.util.Collection;
    +import java.util.function.Consumer;
    +
    +/**
    + * A stage in a command builder where requirements have already been specified. The next stage is a
    + * {@link HasExecutionCommandBuilder} from {@link #executing(Consumer)}. Additional requirements may
    + * still be added before moving on to the next stage.
    + */
    +public interface HasRequirementsCommandBuilder {
    +  /**
    +   * Sets the priority level of the command.
    +   *
    +   * @param priority The desired priority level.
    +   * @return This builder object, for chaining.
    +   */
    +  HasRequirementsCommandBuilder withPriority(int priority);
    +
    +  /**
    +   * Adds a required mechanism for the command.
    +   *
    +   * @param requirement A required mechanism. Cannot be null.
    +   * @return This builder object, for chaining
    +   * @throws NullPointerException If {@code requirement} is null
    +   */
    +  HasRequirementsCommandBuilder requiring(Mechanism requirement);
    +
    +  /**
    +   * Adds one or more required mechanisms for the command.
    +   *
    +   * @param requirement A required mechanism. Cannot be null.
    +   * @param extra Any extra required mechanisms. May be empty, but cannot contain null values.
    +   * @return This builder object, for chaining
    +   * @throws NullPointerException If {@code requirement} is null or {@code extra} contains a null
    +   *     value
    +   */
    +  HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra);
    +
    +  /**
    +   * Adds required mechanisms for the command.
    +   *
    +   * @param requirements Any required mechanisms. May be empty, but cannot contain null values.
    +   * @return This builder object, for chaining
    +   * @throws NullPointerException If {@code requirements} is null or contains a null value.
    +   */
    +  HasRequirementsCommandBuilder requiring(Collection requirements);
    +
    +  /**
    +   * Optionally sets a callback to execute when the command is canceled. The callback will not run
    +   * if the command was canceled after being scheduled but before starting to run, and will not run
    +   * if the command completes naturally or from encountering an unhandled exception.
    +   *
    +   * @param onCancel The function to execute when the command is canceled while running.
    +   * @return This builder object, for chaining
    +   * @throws NullPointerException If {@code onCancel} is null.
    +   */
    +  HasRequirementsCommandBuilder whenCanceled(Runnable onCancel);
    +
    +  /**
    +   * Sets the function body of the executing command.
    +   *
    +   * @param impl The command's body. Cannot be null.
    +   * @return A builder for the next stage of command construction.
    +   * @throws NullPointerException If {@code impl} is null.
    +   */
    +  HasExecutionCommandBuilder executing(Consumer impl);
    +}
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
    index 7d23631561e..b8a64c0d97c 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
    @@ -97,8 +97,8 @@ public Command getDefaultCommand() {
        * @param commandBody The main function body of the command.
        * @return The command builder, for further configuration.
        */
    -  public CommandBuilder run(Consumer commandBody) {
    -    return new CommandBuilder().requiring(this).executing(commandBody);
    +  public HasExecutionCommandBuilder run(Consumer commandBody) {
    +    return new StagedCommandBuilder().requiring(this).executing(commandBody);
       }
     
       /**
    @@ -109,7 +109,7 @@ public CommandBuilder run(Consumer commandBody) {
        * @param loopBody The body of the infinite loop.
        * @return The command builder, for further configuration.
        */
    -  public CommandBuilder runRepeatedly(Runnable loopBody) {
    +  public HasExecutionCommandBuilder runRepeatedly(Runnable loopBody) {
         return run(
             coroutine -> {
               while (true) {
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    new file mode 100644
    index 00000000000..c6acc1d0ef2
    --- /dev/null
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    @@ -0,0 +1,301 @@
    +// 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 org.wpilib.commands3;
    +
    +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
    +
    +import java.util.Arrays;
    +import java.util.Collection;
    +import java.util.HashSet;
    +import java.util.Set;
    +import java.util.function.BooleanSupplier;
    +import java.util.function.Consumer;
    +
    +/**
    + * A builder class for commands. Command configuration is done in stages, where later stages have
    + * different configuration options than earlier stages. Commands may only be created after going
    + * through every stage, enforcing the presence of required options. All commands must have a
    + * set of requirements (which may be empty), a name, and an implementation. The builder stages are
    + * defined such that the final stage that creates a command can only be reached after going through
    + * the earlier stages to configure those required options.
    + *
    + * 

    Example usage: + * + *

    {@code
    + * StagedCommandBuilder start = new StagedCommandBuilder();
    + * HasRequirementsCommandBuilder withRequirements = start.requiring(mechanism1, mechanism2);
    + * HasExecutionCommandBuilder withExecution = withRequirements.executing(coroutine -> ...);
    + * TerminalCommandBuilder terminal = withExecution.withName("Example Command");
    + * Command exampleCommand = terminal.make();
    + * }
    + * + *

    Because every method on the builders returns a builder object, these calls can be chained to + * cut down on verbosity and make the code easier to read. This is the recommended style: + * + *

    {@code
    + * Command exampleCommand =
    + *   new StagedCommandBuilder()
    + *     .requiring(mechanism1, mechanism2)
    + *     .executing(coroutine -> ...)
    + *     .withName("Example Command")
    + *     .make();
    + * }
    + * + *

    And can be cut down even further by using helper methods provided by the library: + * + *

    {@code
    + * Command exampleCommand =
    + *   Command
    + *     .requiring(mechanism1, mechanism2)
    + *     .executing(coroutine -> ...)
    + *     .named("Example Command")
    + * }
    + */ +public class StagedCommandBuilder implements StartingCommandBuilder { + private final Set m_requirements = new HashSet<>(); + private Consumer m_impl; + private Runnable m_onCancel = () -> {}; + private String m_name; + private int m_priority = Command.DEFAULT_PRIORITY; + private BooleanSupplier m_endCondition; + + private Command m_builtCommand; + + // Using internal anonymous classes to implement the staged builder APIs, but all backed by the + // state of the enclosing StagedCommandBuilder object + + private final HasRequirementsCommandBuilder m_requirementsView = + new HasRequirementsCommandBuilder() { + @Override + public HasRequirementsCommandBuilder withPriority(int priority) { + throwIfAlreadyBuilt(); + + m_priority = priority; + return this; + } + + @Override + public HasRequirementsCommandBuilder requiring(Mechanism requirement) { + throwIfAlreadyBuilt(); + + requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); + m_requirements.add(requirement); + return this; + } + + @Override + public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra) { + throwIfAlreadyBuilt(); + + requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); + requireNonNullParam(extra, "extra", "StagedCommandBuilder.requiring"); + + for (int i = 0; i < extra.length; i++) { + requireNonNullParam(extra[i], "extra[" + i + "]", "StagedCommandBuilder.requiring"); + } + + m_requirements.add(requirement); + m_requirements.addAll(Arrays.asList(extra)); + return this; + } + + @Override + public HasRequirementsCommandBuilder requiring(Collection requirements) { + throwIfAlreadyBuilt(); + + requireNonNullParam(requirements, "requirements", "StagedCommandBuilder.requiring"); + m_requirements.addAll(requirements); + return this; + } + + @Override + public HasExecutionCommandBuilder executing(Consumer impl) { + throwIfAlreadyBuilt(); + + requireNonNullParam(impl, "impl", "StagedCommandBuilder.executing"); + m_impl = impl; + return m_executionView; + } + + @Override + public HasRequirementsCommandBuilder whenCanceled(Runnable onCancel) { + throwIfAlreadyBuilt(); + + requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled"); + m_onCancel = onCancel; + return this; + } + }; + + private final HasExecutionCommandBuilder m_executionView = + new HasExecutionCommandBuilder() { + @Override + public HasExecutionCommandBuilder whenCanceled(Runnable onCancel) { + throwIfAlreadyBuilt(); + + requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled"); + m_onCancel = onCancel; + return this; + } + + @Override + public HasExecutionCommandBuilder withPriority(int priority) { + throwIfAlreadyBuilt(); + + m_priority = priority; + return this; + } + + @Override + public HasExecutionCommandBuilder until(BooleanSupplier endCondition) { + throwIfAlreadyBuilt(); + + m_endCondition = endCondition; // allowed to be null + return this; + } + + @Override + public TerminalCommandBuilder withName(String name) { + throwIfAlreadyBuilt(); + + requireNonNullParam(name, "name", "StagedCommandBuilder.withName"); + m_name = name; + return m_terminalView; + } + }; + + private final TerminalCommandBuilder m_terminalView = + new TerminalCommandBuilder() { + @Override + public TerminalCommandBuilder whenCanceled(Runnable onCancel) { + throwIfAlreadyBuilt(); + + requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled"); + m_onCancel = onCancel; + return this; + } + + @Override + public TerminalCommandBuilder withPriority(int priority) { + throwIfAlreadyBuilt(); + + m_priority = priority; + return this; + } + + @Override + public Command make() { + throwIfAlreadyBuilt(); + + var command = new BuilderBackedCommand(StagedCommandBuilder.this); + + if (m_endCondition == null) { + // No custom end condition, just return the raw command + m_builtCommand = command; + } else { + // A custom end condition is implemented as a race group, since we cannot modify the + // command + // body to inject the end condition. + m_builtCommand = + new ParallelGroupBuilder().requiring(command).until(m_endCondition).named(m_name); + } + + return m_builtCommand; + } + }; + + private static final class BuilderBackedCommand implements Command { + private final StagedCommandBuilder m_builder; + + private BuilderBackedCommand(StagedCommandBuilder builder) { + m_builder = builder; + } + + @Override + public void run(Coroutine coroutine) { + m_builder.m_impl.accept(coroutine); + } + + @Override + public void onCancel() { + m_builder.m_onCancel.run(); + } + + @Override + public String name() { + return m_builder.m_name; + } + + @Override + public Set requirements() { + return m_builder.m_requirements; + } + + @Override + public int priority() { + return m_builder.m_priority; + } + + @Override + public String toString() { + return name(); + } + } + + @Override + public HasRequirementsCommandBuilder noRequirements() { + throwIfAlreadyBuilt(); + + return m_requirementsView; + } + + @Override + public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra) { + throwIfAlreadyBuilt(); + + requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); + requireNonNullParam(extra, "extra", "StagedCommandBuilder.requiring"); + + for (int i = 0; i < extra.length; i++) { + requireNonNullParam(extra[i], "extra[" + i + "]", "StagedCommandBuilder.requiring"); + } + + m_requirements.add(requirement); + m_requirements.addAll(Arrays.asList(extra)); + return m_requirementsView; + } + + @Override + public HasRequirementsCommandBuilder requiring(Collection requirements) { + throwIfAlreadyBuilt(); + + requireNonNullParam(requirements, "requirements", "StagedCommandBuilder.requiring"); + int i = 0; + for (var mechanism : requirements) { + requireNonNullParam(mechanism, "requirements[" + i + "]", "StagedCommandBuilder.requiring"); + i++; + } + + m_requirements.addAll(requirements); + return m_requirementsView; + } + + @Override + public StartingCommandBuilder withPriority(int priority) { + throwIfAlreadyBuilt(); + + m_priority = priority; + return this; + } + + // Prevent builders from being mutated after command creation + // Weird things could happen like changing requirements, priority level, or even the command + // implementation itself if we didn't prohibit it. + private void throwIfAlreadyBuilt() { + if (m_builtCommand != null) { + throw new IllegalStateException("Command builders cannot be reused"); + } + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java new file mode 100644 index 00000000000..b3fdb42e00a --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java @@ -0,0 +1,59 @@ +// 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 org.wpilib.commands3; + +import java.util.Collection; +import java.util.function.Consumer; + +/** + * The first stage in a command builder. Requirements (or lack thereof) may be specified with {@link + * #requiring(Mechanism)}, {@link #requiring(Mechanism, Mechanism...)}, {@link + * #requiring(Collection)}, or {@link #noRequirements()}, which goes to a {@link + * HasRequirementsCommandBuilder} stage. {@link #withPriority(int)} may be used before requirements + * are specified. + */ +public interface StartingCommandBuilder { + /** + * Explicitly marks the command as requiring no mechanisms. Unless overridden later with {@link + * HasRequirementsCommandBuilder#requiring(Mechanism)} or a similar method, the built command will + * not have ownership over any mechanisms when it runs. Use this for commands that don't need to + * own a mechanism, such as a gyro zeroing command, that does some kind of cleanup task without + * needing to control something. + * + * @return A builder object that can be used to further configure the command. + */ + HasRequirementsCommandBuilder noRequirements(); + + /** + * Marks the command as requiring one or more mechanisms. If only a single mechanism is required, + * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will + * automatically require the mechanism, instead of it needing to be explicitly specified. + * + * @param requirement The first required mechanism. Cannot be null. + * @param extra Any optional extra required mechanisms. May be empty, but cannot be null or + * contain null values. + * @return A builder object that can be used to further configure the command. + */ + HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra); + + /** + * Marks the command as requiring zero or more mechanisms. If only a single mechanism is required, + * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will + * automatically require the mechanism, instead of it needing to be explicitly specified. + * + * @param requirements A collection of required mechanisms. May be empty, but cannot be null or + * contain null values. + * @return A builder object that can be used to further configure the command. + */ + HasRequirementsCommandBuilder requiring(Collection requirements); + + /** + * Sets the priority level of the command. + * + * @param priority The desired priority level. + * @return This builder object, for chaining. + */ + StartingCommandBuilder withPriority(int priority); +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java new file mode 100644 index 00000000000..f474fd035d1 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java @@ -0,0 +1,39 @@ +// 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 org.wpilib.commands3; + +/** + * The final stage of building a command. The only options available here are setting the {@link + * Command#onCancel()} callback and priority level; otherwise, a command may be created with {@link + * #make()} based on the configurations applied by the previous builder stages. + */ +public interface TerminalCommandBuilder { + /** + * Optionally sets a callback to execute when the command is canceled. The callback will not run + * if the command was canceled after being scheduled but before starting to run, and will not run + * if the command completes naturally or from encountering an unhandled exception. + * + * @param onCancel The function to execute when the command is canceled while running. + * @return This builder object, for chaining. + * @throws NullPointerException If {@code onCancel} is null. + */ + TerminalCommandBuilder whenCanceled(Runnable onCancel); + + /** + * Sets the priority level of the command. + * + * @param priority The desired priority level. + * @return This builder object, for chaining. + */ + TerminalCommandBuilder withPriority(int priority); + + /** + * Creates the command based on the options set during the previous builder stages. The builders + * will no longer be usable after calling this method. + * + * @return The built command. + */ + Command make(); +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index a3ae2acaa09..89ba7720961 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -33,7 +33,7 @@ * needing to create dozens of global triggers. * *
    {@code
    - * Command shootWhileAiming = Command.noRequirements(co -> {
    + * Command shootWhileAiming = Command.noRequirements().executing(co -> {
      *   turret.atTarget.onTrue(shooter.shootOnce());
      *   co.await(turret.lockOnGoal());
      * }).named("Shoot While Aiming");
    diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java
    index df9129b748d..bb8001397b6 100644
    --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java
    +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java
    @@ -34,7 +34,8 @@ void forkMany() {
         var c = new NullCommand();
     
         var all =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.fork(a, b, c);
                       co.park();
    @@ -54,7 +55,8 @@ void yieldInSynchronizedBlock() {
         AtomicInteger i = new AtomicInteger(0);
     
         var yieldInSynchronized =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       while (true) {
                         synchronized (mutex) {
    @@ -85,7 +87,8 @@ void yieldInLockBody() {
         AtomicInteger i = new AtomicInteger(0);
     
         var yieldInLock =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       while (true) {
                         lock.lock();
    @@ -109,7 +112,8 @@ void coroutineEscapingCommand() {
         AtomicReference escapeeCallback = new AtomicReference<>();
     
         var badCommand =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       escapeeCallback.set(co::yield);
                     })
    @@ -130,10 +134,12 @@ void coroutineEscapingCommand() {
       @Test
       void usingParentCoroutineInChildThrows() {
         var parent =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     parentCoroutine -> {
                       parentCoroutine.await(
    -                      Command.noRequirements(
    +                      Command.noRequirements()
    +                          .executing(
                                   childCoroutine -> {
                                     parentCoroutine.yield();
                                   })
    @@ -157,9 +163,10 @@ void awaitAnyCleansUp() {
         AtomicBoolean secondRan = new AtomicBoolean(false);
         AtomicBoolean ranAfterAwait = new AtomicBoolean(false);
     
    -    var firstInner = Command.noRequirements(c2 -> firstRan.set(true)).named("First");
    +    var firstInner = Command.noRequirements().executing(c2 -> firstRan.set(true)).named("First");
         var secondInner =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     c2 -> {
                       secondRan.set(true);
                       c2.park();
    @@ -167,7 +174,8 @@ void awaitAnyCleansUp() {
                 .named("Second");
     
         var outer =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.awaitAny(firstInner, secondInner);
     
    diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
    index 2d112400013..1a6e09af7d3 100644
    --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
    +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
    @@ -207,9 +207,9 @@ void nested() {
     
       @Test
       void automaticNameRace() {
    -    var a = Command.noRequirements(coroutine -> {}).named("A");
    -    var b = Command.noRequirements(coroutine -> {}).named("B");
    -    var c = Command.noRequirements(coroutine -> {}).named("C");
    +    var a = Command.noRequirements().executing(coroutine -> {}).named("A");
    +    var b = Command.noRequirements().executing(coroutine -> {}).named("B");
    +    var c = Command.noRequirements().executing(coroutine -> {}).named("C");
     
         var group = ParallelGroup.builder().optional(a, b, c).withAutomaticName();
         assertEquals("(A | B | C)", group.name());
    @@ -217,9 +217,9 @@ void automaticNameRace() {
     
       @Test
       void automaticNameAll() {
    -    var a = Command.noRequirements(coroutine -> {}).named("A");
    -    var b = Command.noRequirements(coroutine -> {}).named("B");
    -    var c = Command.noRequirements(coroutine -> {}).named("C");
    +    var a = Command.noRequirements().executing(coroutine -> {}).named("A");
    +    var b = Command.noRequirements().executing(coroutine -> {}).named("B");
    +    var c = Command.noRequirements().executing(coroutine -> {}).named("C");
     
         var group = ParallelGroup.builder().requiring(a, b, c).withAutomaticName();
         assertEquals("(A & B & C)", group.name());
    @@ -227,9 +227,9 @@ void automaticNameAll() {
     
       @Test
       void automaticNameDeadline() {
    -    var a = Command.noRequirements(coroutine -> {}).named("A");
    -    var b = Command.noRequirements(coroutine -> {}).named("B");
    -    var c = Command.noRequirements(coroutine -> {}).named("C");
    +    var a = Command.noRequirements().executing(coroutine -> {}).named("A");
    +    var b = Command.noRequirements().executing(coroutine -> {}).named("B");
    +    var c = Command.noRequirements().executing(coroutine -> {}).named("C");
     
         var group = ParallelGroup.builder().requiring(a).optional(b, c).withAutomaticName();
         assertEquals("[(A) * (B | C)]", group.name());
    diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
    index 4244b17cbb6..0ed616f9053 100644
    --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
    +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
    @@ -39,7 +39,8 @@ void basic() {
         var enabled = new AtomicBoolean(false);
         var ran = new AtomicBoolean(false);
         var command =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     coroutine -> {
                       do {
                         coroutine.yield();
    @@ -133,7 +134,8 @@ void atomicity() {
     
         for (int cmdCount = 0; cmdCount < numCommands; cmdCount++) {
           var command =
    -          Command.noRequirements(
    +          Command.noRequirements()
    +              .executing(
                       coroutine -> {
                         for (int i = 0; i < iterations; i++) {
                           coroutine.yield();
    @@ -189,14 +191,17 @@ void errorDetection() {
       @Test
       void nestedErrorDetection() {
         var command =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.await(
    -                      Command.noRequirements(
    +                      Command.noRequirements()
    +                          .executing(
                                   c2 -> {
                                     new Trigger(m_scheduler, () -> true)
                                         .onTrue(
    -                                        Command.noRequirements(
    +                                        Command.noRequirements()
    +                                            .executing(
                                                     c3 -> {
                                                       // Throws IndexOutOfBoundsException
                                                       new ArrayList<>(0).get(-1);
    @@ -335,7 +340,7 @@ void scheduleOverDefaultDoesNotRescheduleDefault() {
     
       @Test
       void cancelsEvictsOnDeck() {
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         m_scheduler.schedule(command);
         m_scheduler.cancel(command);
         assertFalse(m_scheduler.isScheduledOrRunning(command));
    @@ -343,7 +348,7 @@ void cancelsEvictsOnDeck() {
     
       @Test
       void cancelAlEvictsOnDeck() {
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         m_scheduler.schedule(command);
         m_scheduler.cancelAll();
         assertFalse(m_scheduler.isScheduledOrRunning(command));
    @@ -353,7 +358,7 @@ void cancelAlEvictsOnDeck() {
       void cancelAllCancelsAll() {
         var commands = new ArrayList(10);
         for (int i = 1; i <= 10; i++) {
    -      commands.add(Command.noRequirements(Coroutine::yield).named("Command " + i));
    +      commands.add(Command.noRequirements().executing(Coroutine::yield).named("Command " + i));
         }
         commands.forEach(m_scheduler::schedule);
         m_scheduler.run();
    @@ -372,8 +377,7 @@ void cancelAllStartsDefaults() {
           mechanisms.add(new Mechanism("System " + i, m_scheduler));
         }
     
    -    var command =
    -        new CommandBuilder().requiring(mechanisms).executing(Coroutine::yield).named("Big Command");
    +    var command = Command.requiring(mechanisms).executing(Coroutine::yield).named("Big Command");
     
         // Scheduling the command should evict the on-deck default commands
         m_scheduler.schedule(command);
    @@ -411,16 +415,20 @@ void cancelAllStartsDefaults() {
       @Test
       void cancelDeeplyNestedCompositions() {
         Command root =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.await(
    -                      Command.noRequirements(
    +                      Command.noRequirements()
    +                          .executing(
                                   co2 -> {
                                     co2.await(
    -                                    Command.noRequirements(
    +                                    Command.noRequirements()
    +                                        .executing(
                                                 co3 -> {
                                                   co3.await(
    -                                                  Command.noRequirements(Coroutine::park)
    +                                                  Command.noRequirements()
    +                                                      .executing(Coroutine::park)
                                                           .named("Park"));
                                                 })
                                             .named("C3"));
    @@ -492,7 +500,8 @@ void compositionsDoNotNeedRequirements() {
     
         // the group has no requirements, but can schedule child commands that do
         var group =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.awaitAll(
                           m1.run(Coroutine::park).named("M1 Command"),
    @@ -511,7 +520,8 @@ void compositionsCannotAwaitConflictingCommands() {
         var mech = new Mechanism("The mechanism", m_scheduler);
     
         var group =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.awaitAll(
                           mech.run(Coroutine::park).named("First"),
    @@ -674,8 +684,8 @@ void protobuf() {
         m_scheduler.schedule(group);
         m_scheduler.run();
     
    -    var scheduledCommand1 = Command.noRequirements(Coroutine::park).named("Command 1");
    -    var scheduledCommand2 = Command.noRequirements(Coroutine::park).named("Command 2");
    +    var scheduledCommand1 = Command.noRequirements().executing(Coroutine::park).named("Command 1");
    +    var scheduledCommand2 = Command.noRequirements().executing(Coroutine::park).named("Command 2");
         m_scheduler.schedule(scheduledCommand1);
         m_scheduler.schedule(scheduledCommand2);
     
    @@ -791,7 +801,8 @@ void siblingsInCompositionCanShareRequirements() {
                 .named("Second");
     
         var group =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.fork(first);
                       co.fork(second);
    @@ -814,21 +825,25 @@ void siblingsInCompositionCanShareRequirements() {
       void nestedOneShotCompositionsAllRunInOneCycle() {
         var runs = new AtomicInteger(0);
         Supplier makeOneShot =
    -        () -> Command.noRequirements(_c -> runs.incrementAndGet()).named("One Shot");
    +        () -> Command.noRequirements().executing(_c -> runs.incrementAndGet()).named("One Shot");
         var command =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.fork(makeOneShot.get());
                       co.fork(makeOneShot.get());
                       co.fork(
    -                      Command.noRequirements(inner -> inner.fork(makeOneShot.get()))
    +                      Command.noRequirements()
    +                          .executing(inner -> inner.fork(makeOneShot.get()))
                               .named("Inner"));
                       co.fork(
    -                      Command.noRequirements(
    +                      Command.noRequirements()
    +                          .executing(
                                   co2 -> {
                                     co2.fork(makeOneShot.get());
                                     co2.fork(
    -                                    Command.noRequirements(
    +                                    Command.noRequirements()
    +                                        .executing(
                                                 co3 -> {
                                                   co3.fork(makeOneShot.get());
                                                 })
    @@ -852,7 +867,7 @@ void childConflictsWithHigherPriorityTopLevel() {
         // Child conflicts with and is lower priority than the Top command
         // It should not be scheduled, and the parent command should exit immediately
         var child = mechanism.run(Coroutine::park).named("Child");
    -    var parent = Command.noRequirements(co -> co.await(child)).named("Parent");
    +    var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent");
     
         m_scheduler.schedule(top);
         m_scheduler.schedule(parent);
    @@ -871,7 +886,7 @@ void childConflictsWithLowerPriorityTopLevel() {
         // Child conflicts with and is lower priority than the Top command
         // It should not be scheduled, and the parent command should exit immediately
         var child = mechanism.run(Coroutine::park).named("Child");
    -    var parent = Command.noRequirements(co -> co.await(child)).named("Parent");
    +    var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent");
     
         m_scheduler.schedule(top);
         m_scheduler.schedule(parent);
    @@ -888,7 +903,8 @@ void commandAwaitingItself() {
         // equivalent to calling Coroutine.park(). No deleterious side effects other than stalling
         // the command
         AtomicReference commandRef = new AtomicReference<>();
    -    var command = Command.noRequirements(co -> co.await(commandRef.get())).named("Self Await");
    +    var command =
    +        Command.noRequirements().executing(co -> co.await(commandRef.get())).named("Self Await");
         commandRef.set(command);
     
         m_scheduler.schedule(command);
    @@ -911,8 +927,10 @@ void commandDeadlock() {
         //
         // Externally cancelling command2 allows command1 to continue
         // Externally cancelling command1 cancels both
    -    var command1 = Command.noRequirements(co -> co.await(ref2.get())).named("Command 1");
    -    var command2 = Command.noRequirements(co -> co.await(ref1.get())).named("Command 2");
    +    var command1 =
    +        Command.noRequirements().executing(co -> co.await(ref2.get())).named("Command 1");
    +    var command2 =
    +        Command.noRequirements().executing(co -> co.await(ref1.get())).named("Command 2");
         ref1.set(command1);
         ref2.set(command2);
     
    diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java
    index 2d0c356277f..97aac7680f5 100644
    --- a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java
    +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java
    @@ -21,7 +21,7 @@ void setup() {
     
       @Test
       void single() {
    -    var command = Command.noRequirements(Coroutine::yield).named("The Command");
    +    var command = Command.noRequirements().executing(Coroutine::yield).named("The Command");
     
         var sequence = new Sequence("The Sequence", List.of(command));
         m_scheduler.schedule(sequence);
    @@ -44,8 +44,8 @@ void single() {
     
       @Test
       void twoCommands() {
    -    var c1 = Command.noRequirements(Coroutine::yield).named("C1");
    -    var c2 = Command.noRequirements(Coroutine::yield).named("C2");
    +    var c1 = Command.noRequirements().executing(Coroutine::yield).named("C1");
    +    var c2 = Command.noRequirements().executing(Coroutine::yield).named("C2");
     
         var sequence = new Sequence("C1 > C2", List.of(c1, c2));
         m_scheduler.schedule(sequence);
    diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java
    index 89703333304..f4db4675f0f 100644
    --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java
    +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java
    @@ -27,7 +27,7 @@ void setup() {
       void onTrue() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.onTrue(command);
     
         signal.set(true);
    @@ -44,7 +44,7 @@ void onTrue() {
       void onFalse() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.onFalse(command);
     
         m_scheduler.run();
    @@ -61,7 +61,7 @@ void onFalse() {
       void whileTrue() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.whileTrue(command);
     
         signal.set(true);
    @@ -78,7 +78,7 @@ void whileTrue() {
       void whileFalse() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.whileFalse(command);
     
         m_scheduler.run();
    @@ -94,7 +94,7 @@ void whileFalse() {
       void toggleOnTrue() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.toggleOnTrue(command);
     
         m_scheduler.run();
    @@ -117,7 +117,7 @@ void toggleOnTrue() {
       void toggleOnFalse() {
         var signal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, signal::get);
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.toggleOnFalse(command);
     
         m_scheduler.run();
    @@ -138,7 +138,8 @@ void commandScoping() {
         var innerSignal = new AtomicBoolean(false);
     
         var inner =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       while (true) {
                         innerRan.set(true);
    @@ -148,7 +149,8 @@ void commandScoping() {
                 .named("Inner");
     
         var outer =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       new Trigger(m_scheduler, innerSignal::get).onTrue(inner);
                       // If we yield, then the outer command exits and immediately cancels the
    @@ -178,7 +180,7 @@ void scopeGoingInactiveCancelsBoundCommand() {
         var triggerSignal = new AtomicBoolean(false);
         var trigger = new Trigger(m_scheduler, triggerSignal::get);
     
    -    var command = Command.noRequirements(Coroutine::park).named("Command");
    +    var command = Command.noRequirements().executing(Coroutine::park).named("Command");
         trigger.addBinding(scope, BindingType.RUN_WHILE_HIGH, command);
     
         triggerSignal.set(true);
    @@ -201,7 +203,8 @@ void triggerFromExitingCommandDoesNotFire() {
         var triggeredCommandRan = new AtomicBoolean(false);
     
         var inner =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       triggeredCommandRan.set(true);
                       co.park();
    @@ -209,7 +212,8 @@ void triggerFromExitingCommandDoesNotFire() {
                 .named("Inner");
     
         var awaited =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       co.yield();
                       condition.set(true);
    @@ -217,7 +221,8 @@ void triggerFromExitingCommandDoesNotFire() {
                 .named("Awaited");
     
         var outer =
    -        Command.noRequirements(
    +        Command.noRequirements()
    +            .executing(
                     co -> {
                       new Trigger(m_scheduler, condition::get).onTrue(inner);
                       co.await(awaited);
    
    From 3d49867e7e2dddf853b24b6399446169ef0ceff8 Mon Sep 17 00:00:00 2001
    From: Sam Carlberg 
    Date: Mon, 18 Aug 2025 23:37:39 -0400
    Subject: [PATCH 094/153] Update design doc with builder changes
    
    ---
     design-docs/commands-v3.md | 22 ++++++++++++++++++++--
     1 file changed, 20 insertions(+), 2 deletions(-)
    
    diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md
    index 9c46988bfaf..908ad18dc49 100644
    --- a/design-docs/commands-v3.md
    +++ b/design-docs/commands-v3.md
    @@ -144,7 +144,7 @@ void bindDriveButtons() {
     Trigger atScoringPosition = new Trigger(() -> getPosition().isNear(kScoringPosition));
     
     Command autonomous() {
    -  return Command.noRequirements(coroutine -> {
    +  return Command.noRequirements().executing(coroutine -> {
         // This binding only exists while the autonomous command is running
         atScoringPosition.onTrue(score());
     
    @@ -199,7 +199,7 @@ outside its command makes no sense, and an error will be thrown if attempting to
     
     ```java
     Coroutine coroutine;
    -var badCommand = Command.noRequirements(co -> {
    +var badCommand = Command.noRequirements().executing(co -> {
       coroutine = co;
     }).named("Do not do this");
     
    @@ -291,6 +291,24 @@ are cancelled at this point.
     In contrast with v2’s decorator API that returns a new command object for each modification (which
     had some issues with naming and making telemetry difficult with deeply nested wrapper objects), v3
     uses builder objects that allow configuration to be set before creating a single command at the end.
    +Builders are defined in stages, with a different type representing each stage, in order to leverage
    +the type system to prevent users from creating invalid commands and only discovering so at runtime.
    +Failure to apply required configuration options (eg the main command function or a name) will leave
    +users with an intermediate-stage builder that cannot be used to create a command, resulting in a
    +compilation error.
    +
    +```java
    +// OK - requirements, body, and name are all provided
    +// Each builder method returns a different builder object that provides methods
    +// for progressing to the next stage.
    +Command command = Command.noRequirements().executing(...).withName("Name").make()
    +
    +// Compilation error! Missing the command body
    +Command command = Command.noRequirements().withName("Name").make();
    +
    +// Compilation error! Missing the command name
    +Command command = Command.noRequirements().executing(...).make();
    +```
     
     #### Forced Naming
     
    
    From 87696c3e4659776d88f146b9503b823a88257a1a Mon Sep 17 00:00:00 2001
    From: Sam Carlberg 
    Date: Mon, 18 Aug 2025 23:53:13 -0400
    Subject: [PATCH 095/153] Allow `onCancel` callback to be null
    
    Falls back to a no-op runnable
    ---
     .../commands3/HasExecutionCommandBuilder.java |  4 ++--
     .../HasRequirementsCommandBuilder.java        |  4 ++--
     .../commands3/StagedCommandBuilder.java       | 21 +++++++++++++------
     .../commands3/TerminalCommandBuilder.java     |  4 ++--
     4 files changed, 21 insertions(+), 12 deletions(-)
    
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    index 0cad1c144f1..294b65ac05f 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    @@ -19,9 +19,9 @@ public interface HasExecutionCommandBuilder {
        * if the command was canceled after being scheduled but before starting to run, and will not run
        * if the command completes naturally or from encountering an unhandled exception.
        *
    -   * @param onCancel The function to execute when the command is canceled while running.
    +   * @param onCancel The function to execute when the command is canceled while running. May be
    +   *     null.
        * @return This builder object, for chaining
    -   * @throws NullPointerException If {@code onCancel} is null.
        */
       HasExecutionCommandBuilder whenCanceled(Runnable onCancel);
     
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    index e4d9afa39d0..5dbde82623b 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    @@ -55,9 +55,9 @@ public interface HasRequirementsCommandBuilder {
        * if the command was canceled after being scheduled but before starting to run, and will not run
        * if the command completes naturally or from encountering an unhandled exception.
        *
    -   * @param onCancel The function to execute when the command is canceled while running.
    +   * @param onCancel The function to execute when the command is canceled while running. May be
    +   *     null.
        * @return This builder object, for chaining
    -   * @throws NullPointerException If {@code onCancel} is null.
        */
       HasRequirementsCommandBuilder whenCanceled(Runnable onCancel);
     
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    index c6acc1d0ef2..b2da031c5b3 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    @@ -123,8 +123,11 @@ public HasExecutionCommandBuilder executing(Consumer impl) {
             public HasRequirementsCommandBuilder whenCanceled(Runnable onCancel) {
               throwIfAlreadyBuilt();
     
    -          requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled");
    -          m_onCancel = onCancel;
    +          if (onCancel == null) {
    +            m_onCancel = () -> {};
    +          } else {
    +            m_onCancel = onCancel;
    +          }
               return this;
             }
           };
    @@ -135,8 +138,11 @@ public HasRequirementsCommandBuilder whenCanceled(Runnable onCancel) {
             public HasExecutionCommandBuilder whenCanceled(Runnable onCancel) {
               throwIfAlreadyBuilt();
     
    -          requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled");
    -          m_onCancel = onCancel;
    +          if (onCancel == null) {
    +            m_onCancel = () -> {};
    +          } else {
    +            m_onCancel = onCancel;
    +          }
               return this;
             }
     
    @@ -172,8 +178,11 @@ public TerminalCommandBuilder withName(String name) {
             public TerminalCommandBuilder whenCanceled(Runnable onCancel) {
               throwIfAlreadyBuilt();
     
    -          requireNonNullParam(onCancel, "onCancel", "StagedCommandBuilder.whenCanceled");
    -          m_onCancel = onCancel;
    +          if (onCancel == null) {
    +            m_onCancel = () -> {};
    +          } else {
    +            m_onCancel = onCancel;
    +          }
               return this;
             }
     
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java
    index f474fd035d1..ef2e7ba3a2b 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java
    @@ -15,9 +15,9 @@ public interface TerminalCommandBuilder {
        * if the command was canceled after being scheduled but before starting to run, and will not run
        * if the command completes naturally or from encountering an unhandled exception.
        *
    -   * @param onCancel The function to execute when the command is canceled while running.
    +   * @param onCancel The function to execute when the command is canceled while running. May be
    +   *     null.
        * @return This builder object, for chaining.
    -   * @throws NullPointerException If {@code onCancel} is null.
        */
       TerminalCommandBuilder whenCanceled(Runnable onCancel);
     
    
    From b1ac4571c239d8464ac57dbdfe172d7818680cb7 Mon Sep 17 00:00:00 2001
    From: Sam Carlberg 
    Date: Tue, 19 Aug 2025 18:51:21 -0400
    Subject: [PATCH 096/153] Streamline command builder stages
    
    Builders progress from no configuration -> requirements -> execution -> command
    
    Priority levels can now only be set in the execution stage to keep them in a consistent location when using builders
    ---
     .../commands3/HasExecutionCommandBuilder.java |  24 +-
     .../HasRequirementsCommandBuilder.java        |  19 --
     .../commands3/StagedCommandBuilder.java       |  99 ++-----
     .../commands3/StartingCommandBuilder.java     |  11 +-
     .../commands3/TerminalCommandBuilder.java     |  39 ---
     .../commands3/StagedCommandBuilderTest.java   | 254 ++++++++++++++++++
     design-docs/commands-v3.md                    |   6 +-
     7 files changed, 291 insertions(+), 161 deletions(-)
     delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java
     create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java
    
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    index 294b65ac05f..cfbc8e230de 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java
    @@ -9,9 +9,8 @@
     
     /**
      * A stage in a command builder where requirements and main command execution logic have been set.
    - * No more changes to requirements or command implementation may happen after this point. The next
    - * stage is a {@link TerminalCommandBuilder} with {@link #withName(String)}, or straight to a new
    - * command using {@link #named(String)} as shorthand for {@code withName(name).make()}.
    + * No more changes to requirements or command implementation may happen after this point. This is
    + * the final step in command creation
      */
     public interface HasExecutionCommandBuilder {
       /**
    @@ -44,25 +43,12 @@ public interface HasExecutionCommandBuilder {
       HasExecutionCommandBuilder until(BooleanSupplier endCondition);
     
       /**
    -   * Sets the name of the command. {@link #named(String)} can be used instead if no other
    -   * configuration is necessary after this point.
    -   *
    -   * @param name The name of the command. Cannot be null.
    -   * @return A terminal builder object that can be used to create the command.
    -   * @throws NullPointerException If {@code name} is null.
    -   */
    -  TerminalCommandBuilder withName(String name);
    -
    -  /**
    -   * Creates the command based on the options set during the previous builder stages. The builders
    -   * will no longer be usable after calling this method. Shorthand for {@code
    -   * withName(name).make()}.
    +   * Creates the command based on the options set during previous builder stages. The builders will
    +   * no longer be usable after calling this method.
        *
        * @param name The name of the command
        * @return The built command.
        * @throws NullPointerException If {@code name} is null.
        */
    -  default Command named(String name) {
    -    return withName(name).make();
    -  }
    +  Command named(String name);
     }
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    index 5dbde82623b..c9d62ae5027 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java
    @@ -13,14 +13,6 @@
      * still be added before moving on to the next stage.
      */
     public interface HasRequirementsCommandBuilder {
    -  /**
    -   * Sets the priority level of the command.
    -   *
    -   * @param priority The desired priority level.
    -   * @return This builder object, for chaining.
    -   */
    -  HasRequirementsCommandBuilder withPriority(int priority);
    -
       /**
        * Adds a required mechanism for the command.
        *
    @@ -50,17 +42,6 @@ public interface HasRequirementsCommandBuilder {
        */
       HasRequirementsCommandBuilder requiring(Collection requirements);
     
    -  /**
    -   * Optionally sets a callback to execute when the command is canceled. The callback will not run
    -   * if the command was canceled after being scheduled but before starting to run, and will not run
    -   * if the command completes naturally or from encountering an unhandled exception.
    -   *
    -   * @param onCancel The function to execute when the command is canceled while running. May be
    -   *     null.
    -   * @return This builder object, for chaining
    -   */
    -  HasRequirementsCommandBuilder whenCanceled(Runnable onCancel);
    -
       /**
        * Sets the function body of the executing command.
        *
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    index b2da031c5b3..dcd26f6fd75 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java
    @@ -27,8 +27,7 @@
      * StagedCommandBuilder start = new StagedCommandBuilder();
      * HasRequirementsCommandBuilder withRequirements = start.requiring(mechanism1, mechanism2);
      * HasExecutionCommandBuilder withExecution = withRequirements.executing(coroutine -> ...);
    - * TerminalCommandBuilder terminal = withExecution.withName("Example Command");
    - * Command exampleCommand = terminal.make();
    + * Command exampleCommand = withExecution.named("Example Command");
      * }
    * *

    Because every method on the builders returns a builder object, these calls can be chained to @@ -39,8 +38,7 @@ * new StagedCommandBuilder() * .requiring(mechanism1, mechanism2) * .executing(coroutine -> ...) - * .withName("Example Command") - * .make(); + * .named("Example Command"); * }

    * *

    And can be cut down even further by using helper methods provided by the library: @@ -50,10 +48,10 @@ * Command * .requiring(mechanism1, mechanism2) * .executing(coroutine -> ...) - * .named("Example Command") + * .named("Example Command"); * }

  • */ -public class StagedCommandBuilder implements StartingCommandBuilder { +public final class StagedCommandBuilder implements StartingCommandBuilder { private final Set m_requirements = new HashSet<>(); private Consumer m_impl; private Runnable m_onCancel = () -> {}; @@ -68,14 +66,6 @@ public class StagedCommandBuilder implements StartingCommandBuilder { private final HasRequirementsCommandBuilder m_requirementsView = new HasRequirementsCommandBuilder() { - @Override - public HasRequirementsCommandBuilder withPriority(int priority) { - throwIfAlreadyBuilt(); - - m_priority = priority; - return this; - } - @Override public HasRequirementsCommandBuilder requiring(Mechanism requirement) { throwIfAlreadyBuilt(); @@ -106,6 +96,13 @@ public HasRequirementsCommandBuilder requiring(Collection requirement throwIfAlreadyBuilt(); requireNonNullParam(requirements, "requirements", "StagedCommandBuilder.requiring"); + int i = 0; + for (Mechanism requirement : requirements) { + requireNonNullParam( + requirement, "requirements[" + i + "]", "StagedCommandBuilder.requiring"); + i++; + } + m_requirements.addAll(requirements); return this; } @@ -118,18 +115,6 @@ public HasExecutionCommandBuilder executing(Consumer impl) { m_impl = impl; return m_executionView; } - - @Override - public HasRequirementsCommandBuilder whenCanceled(Runnable onCancel) { - throwIfAlreadyBuilt(); - - if (onCancel == null) { - m_onCancel = () -> {}; - } else { - m_onCancel = onCancel; - } - return this; - } }; private final HasExecutionCommandBuilder m_executionView = @@ -163,40 +148,11 @@ public HasExecutionCommandBuilder until(BooleanSupplier endCondition) { } @Override - public TerminalCommandBuilder withName(String name) { + public Command named(String name) { throwIfAlreadyBuilt(); requireNonNullParam(name, "name", "StagedCommandBuilder.withName"); m_name = name; - return m_terminalView; - } - }; - - private final TerminalCommandBuilder m_terminalView = - new TerminalCommandBuilder() { - @Override - public TerminalCommandBuilder whenCanceled(Runnable onCancel) { - throwIfAlreadyBuilt(); - - if (onCancel == null) { - m_onCancel = () -> {}; - } else { - m_onCancel = onCancel; - } - return this; - } - - @Override - public TerminalCommandBuilder withPriority(int priority) { - throwIfAlreadyBuilt(); - - m_priority = priority; - return this; - } - - @Override - public Command make() { - throwIfAlreadyBuilt(); var command = new BuilderBackedCommand(StagedCommandBuilder.this); @@ -216,35 +172,44 @@ public Command make() { }; private static final class BuilderBackedCommand implements Command { - private final StagedCommandBuilder m_builder; + private final Set m_requirements; + private final Consumer m_impl; + private final Runnable m_onCancel; + private final String m_name; + private final int m_priority; private BuilderBackedCommand(StagedCommandBuilder builder) { - m_builder = builder; + // Copy builder fields into the command so the builder object can be garbage collected + m_requirements = new HashSet<>(builder.m_requirements); + m_impl = builder.m_impl; + m_onCancel = builder.m_onCancel; + m_name = builder.m_name; + m_priority = builder.m_priority; } @Override public void run(Coroutine coroutine) { - m_builder.m_impl.accept(coroutine); + m_impl.accept(coroutine); } @Override public void onCancel() { - m_builder.m_onCancel.run(); + m_onCancel.run(); } @Override public String name() { - return m_builder.m_name; + return m_name; } @Override public Set requirements() { - return m_builder.m_requirements; + return m_requirements; } @Override public int priority() { - return m_builder.m_priority; + return m_priority; } @Override @@ -291,14 +256,6 @@ public HasRequirementsCommandBuilder requiring(Collection requirement return m_requirementsView; } - @Override - public StartingCommandBuilder withPriority(int priority) { - throwIfAlreadyBuilt(); - - m_priority = priority; - return this; - } - // Prevent builders from being mutated after command creation // Weird things could happen like changing requirements, priority level, or even the command // implementation itself if we didn't prohibit it. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java index b3fdb42e00a..eefab75e109 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java @@ -11,8 +11,7 @@ * The first stage in a command builder. Requirements (or lack thereof) may be specified with {@link * #requiring(Mechanism)}, {@link #requiring(Mechanism, Mechanism...)}, {@link * #requiring(Collection)}, or {@link #noRequirements()}, which goes to a {@link - * HasRequirementsCommandBuilder} stage. {@link #withPriority(int)} may be used before requirements - * are specified. + * HasRequirementsCommandBuilder} stage. */ public interface StartingCommandBuilder { /** @@ -48,12 +47,4 @@ public interface StartingCommandBuilder { * @return A builder object that can be used to further configure the command. */ HasRequirementsCommandBuilder requiring(Collection requirements); - - /** - * Sets the priority level of the command. - * - * @param priority The desired priority level. - * @return This builder object, for chaining. - */ - StartingCommandBuilder withPriority(int priority); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java deleted file mode 100644 index ef2e7ba3a2b..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/TerminalCommandBuilder.java +++ /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. - -package org.wpilib.commands3; - -/** - * The final stage of building a command. The only options available here are setting the {@link - * Command#onCancel()} callback and priority level; otherwise, a command may be created with {@link - * #make()} based on the configurations applied by the previous builder stages. - */ -public interface TerminalCommandBuilder { - /** - * Optionally sets a callback to execute when the command is canceled. The callback will not run - * if the command was canceled after being scheduled but before starting to run, and will not run - * if the command completes naturally or from encountering an unhandled exception. - * - * @param onCancel The function to execute when the command is canceled while running. May be - * null. - * @return This builder object, for chaining. - */ - TerminalCommandBuilder whenCanceled(Runnable onCancel); - - /** - * Sets the priority level of the command. - * - * @param priority The desired priority level. - * @return This builder object, for chaining. - */ - TerminalCommandBuilder withPriority(int priority); - - /** - * Creates the command based on the options set during the previous builder stages. The builders - * will no longer be usable after calling this method. - * - * @return The built command. - */ - Command make(); -} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java new file mode 100644 index 00000000000..dce01323d30 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java @@ -0,0 +1,254 @@ +// 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 org.wpilib.commands3; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertThrows; + +import java.util.Arrays; +import java.util.Collection; +import java.util.List; +import java.util.function.BooleanSupplier; +import java.util.function.Consumer; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class StagedCommandBuilderTest { + private static final Runnable no_op = () -> {}; + + private Mechanism m_mech1; + private Mechanism m_mech2; + + @BeforeEach + void setUp() { + Scheduler scheduler = new Scheduler(); + m_mech1 = new Mechanism("Mech 1", scheduler); + m_mech2 = new Mechanism("Mech 2", scheduler); + } + + // The next two tests are to check that various forms of builder usage are able to compile. + + @Test + void streamlined() { + Command command = + new StagedCommandBuilder() + .noRequirements() + .executing(Coroutine::park) + .until(() -> false) + .named("Name"); + + assertEquals("Name", command.name()); + } + + @Test + void allOptions() { + var mech = new Mechanism("Mech", new Scheduler()); + + Command command = + new StagedCommandBuilder() + .noRequirements() + .requiring(mech) + .requiring(mech, mech) + .requiring(List.of(mech)) + .executing(Coroutine::park) + .whenCanceled(no_op) + .until(() -> false) + .withPriority(10) + .named("Name"); + + assertEquals("Name", command.name()); + } + + @Test + void starting_noRequirements_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + builder.noRequirements().executing(c -> {}).named("cmd"); + + var err = assertThrows(IllegalStateException.class, builder::noRequirements); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void starting_requiringVarargs_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + builder.noRequirements().executing(c -> {}).named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> builder.requiring(m_mech1, m_mech2)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void starting_requiringCollection_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + builder.noRequirements().executing(c -> {}).named("cmd"); + + var err = + assertThrows( + IllegalStateException.class, () -> builder.requiring(List.of(m_mech1, m_mech2))); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void requirements_requiringSingle_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var reqStage = builder.noRequirements(); + reqStage.executing(c -> {}).named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void requirements_requiringVarargs_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var reqStage = builder.noRequirements(); + reqStage.executing(Coroutine::park).named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1, m_mech2)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void requirements_requiringCollection_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var reqStage = builder.noRequirements(); + reqStage.executing(Coroutine::park).named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(List.of(m_mech1))); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void requirements_executing_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var reqStage = builder.noRequirements(); + reqStage.executing(c -> {}).named("cmd"); + + Consumer impl = Coroutine::park; + var err = assertThrows(IllegalStateException.class, () -> reqStage.executing(impl)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void execution_whenCanceled_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var execStage = builder.noRequirements().executing(c -> {}); + execStage.named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> execStage.whenCanceled(() -> {})); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void execution_withPriority_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var execStage = builder.noRequirements().executing(c -> {}); + execStage.named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> execStage.withPriority(7)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void execution_until_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var execStage = builder.noRequirements().executing(c -> {}); + execStage.named("cmd"); + + BooleanSupplier endCondition = () -> true; + var err = assertThrows(IllegalStateException.class, () -> execStage.until(endCondition)); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void execution_named_throwsAfterBuild() { + var builder = new StagedCommandBuilder(); + var execStage = builder.noRequirements().executing(c -> {}); + execStage.named("cmd"); + + var err = assertThrows(IllegalStateException.class, () -> execStage.named("other")); + assertEquals("Command builders cannot be reused", err.getMessage()); + } + + @Test + void starting_requiringVarargs_nullFirstRequirement_throwsNPE() { + var builder = new StagedCommandBuilder(); + assertThrows(NullPointerException.class, () -> builder.requiring(null, m_mech2)); + } + + @Test + void starting_requiringVarargs_nullArray_throwsNPE() { + var builder = new StagedCommandBuilder(); + assertThrows(NullPointerException.class, () -> builder.requiring(m_mech1, (Mechanism[]) null)); + } + + @Test + void starting_requiringVarargs_nullInExtra_throwsNPE() { + var builder = new StagedCommandBuilder(); + assertThrows(NullPointerException.class, () -> builder.requiring(m_mech1, m_mech2, null)); + } + + @Test + void starting_requiringCollection_nullCollection_throwsNPE() { + var builder = new StagedCommandBuilder(); + assertThrows(NullPointerException.class, () -> builder.requiring((Collection) null)); + } + + @Test + void starting_requiringCollection_nullElement_throwsNPE() { + var builder = new StagedCommandBuilder(); + var listWithNull = Arrays.asList(m_mech1, null, m_mech2); // Arrays.asList allows nulls + assertThrows(NullPointerException.class, () -> builder.requiring(listWithNull)); + } + + @Test + void requirements_requiringSingle_null_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.requiring((Mechanism) null)); + } + + @Test + void requirements_requiringVarargs_nullFirstRequirement_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.requiring(null, m_mech2)); + } + + @Test + void requirements_requiringVarargs_nullArray_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.requiring(m_mech1, (Mechanism[]) null)); + } + + @Test + void requirements_requiringVarargs_nullInExtra_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.requiring(m_mech1, m_mech2, null)); + } + + @Test + void requirements_requiringCollection_nullCollection_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.requiring((Collection) null)); + } + + @Test + void requirements_requiringCollection_nullElement_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + var listWithNull = Arrays.asList(m_mech1, null); // Arrays.asList allows nulls + assertThrows(NullPointerException.class, () -> req.requiring(listWithNull)); + } + + @Test + void requirements_executing_nullImpl_throwsNPE() { + var req = new StagedCommandBuilder().noRequirements(); + assertThrows(NullPointerException.class, () -> req.executing(null)); + } + + @Test + void execution_named_nullName_throwsNPE() { + var exec = new StagedCommandBuilder().noRequirements().executing(c -> {}); + assertThrows(NullPointerException.class, () -> exec.named(null)); + } +} diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 908ad18dc49..139bd3a9c9b 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -301,13 +301,13 @@ compilation error. // OK - requirements, body, and name are all provided // Each builder method returns a different builder object that provides methods // for progressing to the next stage. -Command command = Command.noRequirements().executing(...).withName("Name").make() +Command command = Command.noRequirements().executing(...).named("Name"); // Compilation error! Missing the command body -Command command = Command.noRequirements().withName("Name").make(); +Command command = Command.noRequirements().named("Name"); // Compilation error! Missing the command name -Command command = Command.noRequirements().executing(...).make(); +Command command = Command.noRequirements().executing(...); ``` #### Forced Naming From 9aceb46422f575e7a1b074feea6c51eab5b8b72b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 20 Aug 2025 20:30:10 -0400 Subject: [PATCH 097/153] Simplify builder stages Remove starting stage, hoisting its functions into StagedCommandBuilder Rename HasRequirements stage to NeedsExecution, and HasExecution to NeedsName to better represent what users need to do at each stage and improve compiler error messages --- .../java/org/wpilib/commands3/Command.java | 8 +- .../java/org/wpilib/commands3/Mechanism.java | 4 +- ...r.java => NeedsExecutionBuilderStage.java} | 17 ++-- ...uilder.java => NeedsNameBuilderStage.java} | 10 +-- .../commands3/StagedCommandBuilder.java | 87 ++++++++++++------- .../commands3/StartingCommandBuilder.java | 50 ----------- 6 files changed, 75 insertions(+), 101 deletions(-) rename commandsv3/src/main/java/org/wpilib/commands3/{HasRequirementsCommandBuilder.java => NeedsExecutionBuilderStage.java} (73%) rename commandsv3/src/main/java/org/wpilib/commands3/{HasExecutionCommandBuilder.java => NeedsNameBuilderStage.java} (84%) delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index f6d9ea8a81e..903bbea0001 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -198,7 +198,7 @@ default Command withTimeout(Time timeout) { * * @return a builder that can be used to configure the resulting command */ - static HasRequirementsCommandBuilder noRequirements() { + static NeedsExecutionBuilderStage noRequirements() { return new StagedCommandBuilder().noRequirements(); } @@ -209,7 +209,7 @@ static HasRequirementsCommandBuilder noRequirements() { * @param rest Any other required mechanisms * @return A command builder */ - static HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... rest) { + static NeedsExecutionBuilderStage requiring(Mechanism requirement, Mechanism... rest) { return new StagedCommandBuilder().requiring(requirement, rest); } @@ -219,7 +219,7 @@ static HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism. * @param requirements The required mechanisms. May be empty, but cannot contain null values. * @return A command builder */ - static HasRequirementsCommandBuilder requiring(Collection requirements) { + static NeedsExecutionBuilderStage requiring(Collection requirements) { return new StagedCommandBuilder().requiring(requirements); } @@ -266,7 +266,7 @@ static SequenceBuilder sequence(Command... commands) { * @param condition The condition to wait for * @return A command builder */ - static HasExecutionCommandBuilder waitUntil(BooleanSupplier condition) { + static NeedsNameBuilderStage waitUntil(BooleanSupplier condition) { return noRequirements().executing(coroutine -> coroutine.waitUntil(condition)); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index b8a64c0d97c..0999f03e6fc 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -97,7 +97,7 @@ public Command getDefaultCommand() { * @param commandBody The main function body of the command. * @return The command builder, for further configuration. */ - public HasExecutionCommandBuilder run(Consumer commandBody) { + public NeedsNameBuilderStage run(Consumer commandBody) { return new StagedCommandBuilder().requiring(this).executing(commandBody); } @@ -109,7 +109,7 @@ public HasExecutionCommandBuilder run(Consumer commandBody) { * @param loopBody The body of the infinite loop. * @return The command builder, for further configuration. */ - public HasExecutionCommandBuilder runRepeatedly(Runnable loopBody) { + public NeedsNameBuilderStage runRepeatedly(Runnable loopBody) { return run( coroutine -> { while (true) { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java similarity index 73% rename from commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java rename to commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java index c9d62ae5027..f781ce502e1 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/HasRequirementsCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java @@ -8,11 +8,12 @@ import java.util.function.Consumer; /** - * A stage in a command builder where requirements have already been specified. The next stage is a - * {@link HasExecutionCommandBuilder} from {@link #executing(Consumer)}. Additional requirements may - * still be added before moving on to the next stage. + * A stage in a command builder where requirements have already been specified and execution details + * are required. The next stage is a {@link NeedsNameBuilderStage} from {@link + * #executing(Consumer)}. Additional requirements may still be added before moving on to the next + * stage. */ -public interface HasRequirementsCommandBuilder { +public interface NeedsExecutionBuilderStage { /** * Adds a required mechanism for the command. * @@ -20,7 +21,7 @@ public interface HasRequirementsCommandBuilder { * @return This builder object, for chaining * @throws NullPointerException If {@code requirement} is null */ - HasRequirementsCommandBuilder requiring(Mechanism requirement); + NeedsExecutionBuilderStage requiring(Mechanism requirement); /** * Adds one or more required mechanisms for the command. @@ -31,7 +32,7 @@ public interface HasRequirementsCommandBuilder { * @throws NullPointerException If {@code requirement} is null or {@code extra} contains a null * value */ - HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra); + NeedsExecutionBuilderStage requiring(Mechanism requirement, Mechanism... extra); /** * Adds required mechanisms for the command. @@ -40,7 +41,7 @@ public interface HasRequirementsCommandBuilder { * @return This builder object, for chaining * @throws NullPointerException If {@code requirements} is null or contains a null value. */ - HasRequirementsCommandBuilder requiring(Collection requirements); + NeedsExecutionBuilderStage requiring(Collection requirements); /** * Sets the function body of the executing command. @@ -49,5 +50,5 @@ public interface HasRequirementsCommandBuilder { * @return A builder for the next stage of command construction. * @throws NullPointerException If {@code impl} is null. */ - HasExecutionCommandBuilder executing(Consumer impl); + NeedsNameBuilderStage executing(Consumer impl); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java similarity index 84% rename from commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java rename to commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java index cfbc8e230de..998481cdc07 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/HasExecutionCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java @@ -12,7 +12,7 @@ * No more changes to requirements or command implementation may happen after this point. This is * the final step in command creation */ -public interface HasExecutionCommandBuilder { +public interface NeedsNameBuilderStage { /** * Optionally sets a callback to execute when the command is canceled. The callback will not run * if the command was canceled after being scheduled but before starting to run, and will not run @@ -22,7 +22,7 @@ public interface HasExecutionCommandBuilder { * null. * @return This builder object, for chaining */ - HasExecutionCommandBuilder whenCanceled(Runnable onCancel); + NeedsNameBuilderStage whenCanceled(Runnable onCancel); /** * Sets the priority level of the command. @@ -30,17 +30,17 @@ public interface HasExecutionCommandBuilder { * @param priority The desired priority level. * @return This builder object, for chaining. */ - HasExecutionCommandBuilder withPriority(int priority); + NeedsNameBuilderStage withPriority(int priority); /** * Optionally sets an end condition for the command. If the end condition returns {@code true} - * before the command body set in {@link HasRequirementsCommandBuilder#executing(Consumer)} would + * before the command body set in {@link NeedsExecutionBuilderStage#executing(Consumer)} would * exit, the command will be cancelled by the scheduler. * * @param endCondition An optional end condition for the command. May be null. * @return This builder object, for chaining. */ - HasExecutionCommandBuilder until(BooleanSupplier endCondition); + NeedsNameBuilderStage until(BooleanSupplier endCondition); /** * Creates the command based on the options set during previous builder stages. The builders will diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java index dcd26f6fd75..7a8d195fd54 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java @@ -9,6 +9,7 @@ import java.util.Arrays; import java.util.Collection; import java.util.HashSet; +import java.util.Objects; import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Consumer; @@ -25,8 +26,8 @@ * *
    {@code
      * StagedCommandBuilder start = new StagedCommandBuilder();
    - * HasRequirementsCommandBuilder withRequirements = start.requiring(mechanism1, mechanism2);
    - * HasExecutionCommandBuilder withExecution = withRequirements.executing(coroutine -> ...);
    + * NeedsExecutionBuilderStage withRequirements = start.requiring(mechanism1, mechanism2);
    + * NeedsNameBuilderStage withExecution = withRequirements.executing(coroutine -> ...);
      * Command exampleCommand = withExecution.named("Example Command");
      * }
    * @@ -51,7 +52,7 @@ * .named("Example Command"); * }
    */ -public final class StagedCommandBuilder implements StartingCommandBuilder { +public final class StagedCommandBuilder { private final Set m_requirements = new HashSet<>(); private Consumer m_impl; private Runnable m_onCancel = () -> {}; @@ -64,10 +65,10 @@ public final class StagedCommandBuilder implements StartingCommandBuilder { // Using internal anonymous classes to implement the staged builder APIs, but all backed by the // state of the enclosing StagedCommandBuilder object - private final HasRequirementsCommandBuilder m_requirementsView = - new HasRequirementsCommandBuilder() { + private final NeedsExecutionBuilderStage m_needsExecutionView = + new NeedsExecutionBuilderStage() { @Override - public HasRequirementsCommandBuilder requiring(Mechanism requirement) { + public NeedsExecutionBuilderStage requiring(Mechanism requirement) { throwIfAlreadyBuilt(); requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); @@ -76,7 +77,7 @@ public HasRequirementsCommandBuilder requiring(Mechanism requirement) { } @Override - public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra) { + public NeedsExecutionBuilderStage requiring(Mechanism requirement, Mechanism... extra) { throwIfAlreadyBuilt(); requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); @@ -92,7 +93,7 @@ public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism. } @Override - public HasRequirementsCommandBuilder requiring(Collection requirements) { + public NeedsExecutionBuilderStage requiring(Collection requirements) { throwIfAlreadyBuilt(); requireNonNullParam(requirements, "requirements", "StagedCommandBuilder.requiring"); @@ -108,31 +109,27 @@ public HasRequirementsCommandBuilder requiring(Collection requirement } @Override - public HasExecutionCommandBuilder executing(Consumer impl) { + public NeedsNameBuilderStage executing(Consumer impl) { throwIfAlreadyBuilt(); requireNonNullParam(impl, "impl", "StagedCommandBuilder.executing"); m_impl = impl; - return m_executionView; + return m_needsNameView; } }; - private final HasExecutionCommandBuilder m_executionView = - new HasExecutionCommandBuilder() { + private final NeedsNameBuilderStage m_needsNameView = + new NeedsNameBuilderStage() { @Override - public HasExecutionCommandBuilder whenCanceled(Runnable onCancel) { + public NeedsNameBuilderStage whenCanceled(Runnable onCancel) { throwIfAlreadyBuilt(); - if (onCancel == null) { - m_onCancel = () -> {}; - } else { - m_onCancel = onCancel; - } + m_onCancel = onCancel; return this; } @Override - public HasExecutionCommandBuilder withPriority(int priority) { + public NeedsNameBuilderStage withPriority(int priority) { throwIfAlreadyBuilt(); m_priority = priority; @@ -140,7 +137,7 @@ public HasExecutionCommandBuilder withPriority(int priority) { } @Override - public HasExecutionCommandBuilder until(BooleanSupplier endCondition) { + public NeedsNameBuilderStage until(BooleanSupplier endCondition) { throwIfAlreadyBuilt(); m_endCondition = endCondition; // allowed to be null @@ -161,8 +158,7 @@ public Command named(String name) { m_builtCommand = command; } else { // A custom end condition is implemented as a race group, since we cannot modify the - // command - // body to inject the end condition. + // command body to inject the end condition. m_builtCommand = new ParallelGroupBuilder().requiring(command).until(m_endCondition).named(m_name); } @@ -172,6 +168,8 @@ public Command named(String name) { }; private static final class BuilderBackedCommand implements Command { + private static final Runnable kNoOp = () -> {}; + private final Set m_requirements; private final Consumer m_impl; private final Runnable m_onCancel; @@ -182,7 +180,7 @@ private BuilderBackedCommand(StagedCommandBuilder builder) { // Copy builder fields into the command so the builder object can be garbage collected m_requirements = new HashSet<>(builder.m_requirements); m_impl = builder.m_impl; - m_onCancel = builder.m_onCancel; + m_onCancel = Objects.requireNonNullElse(builder.m_onCancel, kNoOp); m_name = builder.m_name; m_priority = builder.m_priority; } @@ -218,15 +216,32 @@ public String toString() { } } - @Override - public HasRequirementsCommandBuilder noRequirements() { + /** + * Explicitly marks the command as requiring no mechanisms. Unless overridden later with {@link + * NeedsExecutionBuilderStage#requiring(Mechanism)} or a similar method, the built command will + * not have ownership over any mechanisms when it runs. Use this for commands that don't need to + * own a mechanism, such as a gyro zeroing command, that does some kind of cleanup task without + * needing to control something. + * + * @return A builder object that can be used to further configure the command. + */ + public NeedsExecutionBuilderStage noRequirements() { throwIfAlreadyBuilt(); - return m_requirementsView; + return m_needsExecutionView; } - @Override - public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra) { + /** + * Marks the command as requiring one or more mechanisms. If only a single mechanism is required, + * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will + * automatically require the mechanism, instead of it needing to be explicitly specified. + * + * @param requirement The first required mechanism. Cannot be null. + * @param extra Any optional extra required mechanisms. May be empty, but cannot be null or + * contain null values. + * @return A builder object that can be used to further configure the command. + */ + public NeedsExecutionBuilderStage requiring(Mechanism requirement, Mechanism... extra) { throwIfAlreadyBuilt(); requireNonNullParam(requirement, "requirement", "StagedCommandBuilder.requiring"); @@ -238,11 +253,19 @@ public HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism. m_requirements.add(requirement); m_requirements.addAll(Arrays.asList(extra)); - return m_requirementsView; + return m_needsExecutionView; } - @Override - public HasRequirementsCommandBuilder requiring(Collection requirements) { + /** + * Marks the command as requiring zero or more mechanisms. If only a single mechanism is required, + * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will + * automatically require the mechanism, instead of it needing to be explicitly specified. + * + * @param requirements A collection of required mechanisms. May be empty, but cannot be null or + * contain null values. + * @return A builder object that can be used to further configure the command. + */ + public NeedsExecutionBuilderStage requiring(Collection requirements) { throwIfAlreadyBuilt(); requireNonNullParam(requirements, "requirements", "StagedCommandBuilder.requiring"); @@ -253,7 +276,7 @@ public HasRequirementsCommandBuilder requiring(Collection requirement } m_requirements.addAll(requirements); - return m_requirementsView; + return m_needsExecutionView; } // Prevent builders from being mutated after command creation diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java deleted file mode 100644 index eefab75e109..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/StartingCommandBuilder.java +++ /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. - -package org.wpilib.commands3; - -import java.util.Collection; -import java.util.function.Consumer; - -/** - * The first stage in a command builder. Requirements (or lack thereof) may be specified with {@link - * #requiring(Mechanism)}, {@link #requiring(Mechanism, Mechanism...)}, {@link - * #requiring(Collection)}, or {@link #noRequirements()}, which goes to a {@link - * HasRequirementsCommandBuilder} stage. - */ -public interface StartingCommandBuilder { - /** - * Explicitly marks the command as requiring no mechanisms. Unless overridden later with {@link - * HasRequirementsCommandBuilder#requiring(Mechanism)} or a similar method, the built command will - * not have ownership over any mechanisms when it runs. Use this for commands that don't need to - * own a mechanism, such as a gyro zeroing command, that does some kind of cleanup task without - * needing to control something. - * - * @return A builder object that can be used to further configure the command. - */ - HasRequirementsCommandBuilder noRequirements(); - - /** - * Marks the command as requiring one or more mechanisms. If only a single mechanism is required, - * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will - * automatically require the mechanism, instead of it needing to be explicitly specified. - * - * @param requirement The first required mechanism. Cannot be null. - * @param extra Any optional extra required mechanisms. May be empty, but cannot be null or - * contain null values. - * @return A builder object that can be used to further configure the command. - */ - HasRequirementsCommandBuilder requiring(Mechanism requirement, Mechanism... extra); - - /** - * Marks the command as requiring zero or more mechanisms. If only a single mechanism is required, - * prefer a factory function like {@link Mechanism#run(Consumer)} or similar - it will - * automatically require the mechanism, instead of it needing to be explicitly specified. - * - * @param requirements A collection of required mechanisms. May be empty, but cannot be null or - * contain null values. - * @return A builder object that can be used to further configure the command. - */ - HasRequirementsCommandBuilder requiring(Collection requirements); -} From 9fd03232d287c429d984bd5bf52427b729c14d07 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 21 Aug 2025 18:59:24 -0400 Subject: [PATCH 098/153] Use a counter to issue IDs to CommandStates System.identityHashCode doesn't have uniqueness guarantees, and monotonically increasing IDs are better for telemetry --- .../org/wpilib/commands3/CommandState.java | 22 +++++++++---------- design-docs/commands-v3.md | 9 +++++--- 2 files changed, 17 insertions(+), 14 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index a77d15916a5..66fac4d599e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -6,13 +6,16 @@ /** Represents the state of a command as it is executed by the scheduler. */ final class CommandState { + // Two billion unique IDs should be enough for anybody. + private static int s_lastId = 0; + private final Command m_command; private final Command m_parent; private final Coroutine m_coroutine; private final Binding m_binding; private double m_lastRuntimeMs = -1; private double m_totalRuntimeMs; - private final int m_id = System.identityHashCode(this); + private final int m_id; /** * Creates a new command state object. @@ -31,6 +34,11 @@ final class CommandState { m_parent = parent; m_coroutine = coroutine; m_binding = binding; + + // This is incredibly non-thread safe, but nobody should be using the command framework across + // multiple threads anyway. Worst case scenario, we'll get duplicate IDs for commands scheduled + // by different threads and cause bad telemetry data without affecting program correctness. + m_id = ++s_lastId; } public Command command() { @@ -85,15 +93,7 @@ public int hashCode() { @Override public String toString() { - return "CommandState[" - + "command=" - + m_command - + ", " - + "parent=" - + m_parent - + ", " - + "coroutine=" - + m_coroutine - + ']'; + return "CommandState[command=%s, parent=%s, coroutine=%s, id=%d]" + .formatted(m_command, m_parent, m_coroutine, m_id); } } diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index 139bd3a9c9b..c9685364601 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -388,9 +388,12 @@ last_time_ms: double, total_time_ms: double). Consumers can use the `id` and `pa to reconstruct the tree structure, if desired. `id` and `parent_id` marginally increase the size of serialized data, but make the schema and deserialization quite simple. -Command IDs are the Java system identity hashcode (_not_ object hashcode, which can be overridden -and be identical for different command objects). If a command has no parent, no parent ID will -appear in its message. +Command IDs are unique across all commands, including those that are not currently running. Every time +a command is scheduled, the scheduler will assign that run a unique ID. Note that this is stored as a +32-bit signed integer, so the maximum number of unique IDs is 2^31. No guarantee is made that IDs will +be unique across runs of the same program, nor to the order in which ID numbers are assigned; however, +IDs will be issued in a monotonically increasing fashion - a command scheduled before another will +always have a lower ID number. Records in the serialized output will be ordered by scheduling order. As a result, child commands will always appear _after_ their parent. From 05477bd4fe3e381c6e009e675ed01d44b1b1c1ec Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 23 Aug 2025 11:42:13 -0400 Subject: [PATCH 099/153] Remove old CommandBuilder class --- .../org/wpilib/commands3/CommandBuilder.java | 226 ------------------ 1 file changed, 226 deletions(-) delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java deleted file mode 100644 index 767432094b6..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandBuilder.java +++ /dev/null @@ -1,226 +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 org.wpilib.commands3; - -import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; - -import java.util.Arrays; -import java.util.Collection; -import java.util.HashSet; -import java.util.List; -import java.util.Objects; -import java.util.Set; -import java.util.function.BooleanSupplier; -import java.util.function.Consumer; - -/** - * A builder that allows for all functionality of a command to be configured prior to creating it. - */ -public class CommandBuilder { - private final Set m_requirements = new HashSet<>(); - private Consumer m_impl; - private Runnable m_onCancel = () -> {}; - private String m_name; - private int m_priority = Command.DEFAULT_PRIORITY; - private BooleanSupplier m_endCondition; - - /** - * Adds a mechanism as a requirement for the command. - * - * @param mechanism The required mechanism - * @return The builder object, for chaining - * @see Command#requirements() - */ - public CommandBuilder requiring(Mechanism mechanism) { - requireNonNullParam(mechanism, "mechanism", "CommandBuilder.requiring"); - - m_requirements.add(mechanism); - return this; - } - - /** - * Adds mechanisms as requirements for the command. - * - * @param mechanisms The required mechanisms - * @return The builder object, for chaining - * @see Command#requirements() - */ - public CommandBuilder requiring(Mechanism... mechanisms) { - requireNonNullParam(mechanisms, "mechanisms", "CommandBuilder.requiring"); - for (int i = 0; i < mechanisms.length; i++) { - requireNonNullParam(mechanisms[i], "mechanisms[" + i + "]", "CommandBuilder.requiring"); - } - - m_requirements.addAll(Arrays.asList(mechanisms)); - return this; - } - - /** - * Adds mechanisms as requirements for the command. - * - * @param mechanisms The required mechanisms - * @return The builder object, for chaining - * @see Command#requirements() - */ - public CommandBuilder requiring(Collection mechanisms) { - requireNonNullParam(mechanisms, "mechanisms", "CommandBuilder.requiring"); - if (mechanisms instanceof List l) { - for (int i = 0; i < l.size(); i++) { - requireNonNullParam(l.get(i), "mechanisms[" + i + "]", "CommandBuilder.requiring"); - } - } else { - // non-indexable collection - for (var mechanism : mechanisms) { - requireNonNullParam(mechanism, "mechanisms", "CommandBuilder.requiring"); - } - } - - m_requirements.addAll(mechanisms); - return this; - } - - /** - * Sets the name of the command. - * - * @param name The command's name - * @return The builder object, for chaining - * @see Command#name() - */ - public CommandBuilder withName(String name) { - requireNonNullParam(name, "name", "CommandBuilder.withName"); - - m_name = name; - return this; - } - - /** - * Creates the command based on what's been configured in the builder. - * - * @param name The name of the command - * @return The built command - * @throws NullPointerException if {@code name} is null or if the command body was not set using - * {@link #executing(Consumer)}. - * @see Command#name() - */ - public Command named(String name) { - return withName(name).make(); - } - - /** - * Sets the priority of the command. If not set, {@link Command#DEFAULT_PRIORITY} will be used. - * - * @param priority The priority of the command - * @return The builder object, for chaining - * @see Command#priority() - */ - public CommandBuilder withPriority(int priority) { - m_priority = priority; - return this; - } - - /** - * Sets the code that the command will execute when it's being run by the scheduler. - * - * @param impl The command implementation - * @return The builder object, for chaining - * @see Command#run(Coroutine) - */ - public CommandBuilder executing(Consumer impl) { - requireNonNullParam(impl, "impl", "CommandBuilder.executing"); - - m_impl = impl; - return this; - } - - /** - * Sets the code that the command will execute if it's cancelled while running. - * - * @param onCancel The cancellation callback - * @return The builder object, for chaining. - * @see Command#onCancel() - */ - public CommandBuilder whenCanceled(Runnable onCancel) { - requireNonNullParam(onCancel, "onCancel", "CommandBuilder.whenCanceled"); - - m_onCancel = onCancel; - return this; - } - - /** - * Makes the command run until some end condition is met, if it hasn't already finished by then on - * its own. - * - * @param endCondition The hard end condition for the command. - * @return The builder object, for chaining. - */ - public CommandBuilder until(BooleanSupplier endCondition) { - m_endCondition = endCondition; - return this; - } - - /** - * Makes the command run while some condition is true, ending when the condition becomes inactive. - * - * @param active The command active condition. - * @return The builder object, for chaining. - */ - public CommandBuilder asLongAs(BooleanSupplier active) { - return until(() -> !active.getAsBoolean()); - } - - /** - * Creates the command. - * - * @return The built command - * @throws NullPointerException An NPE if either the command {@link #named(String) name} or {@link - * #executing(Consumer) implementation} were not configured before calling this method. - */ - public Command make() { - Objects.requireNonNull(m_name, "Name was not specified"); - Objects.requireNonNull(m_impl, "Command logic was not specified"); - - var command = - new Command() { - @Override - public void run(Coroutine coroutine) { - m_impl.accept(coroutine); - } - - @Override - public void onCancel() { - m_onCancel.run(); - } - - @Override - public String name() { - return m_name; - } - - @Override - public Set requirements() { - return m_requirements; - } - - @Override - public int priority() { - return m_priority; - } - - @Override - public String toString() { - return m_name; - } - }; - - if (m_endCondition == null) { - // No custom end condition, just return the raw command - return command; - } else { - // A custom end condition is implemented as a race group, since we cannot modify the command - // body to inject the end condition. - return new ParallelGroupBuilder().requiring(command).until(m_endCondition).named(m_name); - } - } -} From 310145e3a437ebe0027ede742edbcd34c693ecfd Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 23 Aug 2025 11:43:15 -0400 Subject: [PATCH 100/153] Make scheduler field private Accessor is already public, no need to use a protected field --- .../java/org/wpilib/commands3/button/CommandGenericHID.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 64860ea14a3..809173f345d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -19,7 +19,7 @@ * @see GenericHID */ public class CommandGenericHID { - protected final Scheduler m_scheduler; + private final Scheduler m_scheduler; private final GenericHID m_hid; private final Map> m_buttonCache = new HashMap<>(); private final Map, Trigger>> m_axisLessThanCache = From f37a806dca72c29c4e1ba626c5788401d9907cb8 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 23 Aug 2025 11:43:30 -0400 Subject: [PATCH 101/153] Include commandsv3 in docs build --- docs/BUILD.bazel | 1 + docs/build.gradle | 3 +++ 2 files changed, 4 insertions(+) diff --git a/docs/BUILD.bazel b/docs/BUILD.bazel index 3153b0234fd..e10c2d553bf 100644 --- a/docs/BUILD.bazel +++ b/docs/BUILD.bazel @@ -107,6 +107,7 @@ javadoc( "//apriltag:apriltag-java", "//cameraserver:cameraserver-java", "//cscore:cscore-java", + "//commandsv3:commandsv3-java", "//epilogue-runtime:epilogue-java", "//hal:hal-java", "//ntcore:ntcore-java", diff --git a/docs/build.gradle b/docs/build.gradle index a97c8c33f4d..22e01d63e2b 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -5,6 +5,7 @@ plugins { evaluationDependsOn(':apriltag') evaluationDependsOn(':cameraserver') +evaluationDependsOn(':commandsv3') evaluationDependsOn(':cscore') evaluationDependsOn(':epilogue-runtime') evaluationDependsOn(':hal') @@ -204,6 +205,7 @@ task generateJavaDocs(type: Javadoc) { "-edu.wpi.first.math.system.plant.proto," + "-edu.wpi.first.math.system.plant.struct," + "-edu.wpi.first.math.trajectory.proto," + + "-org.wpilib.commands3.proto," + // The .measure package contains generated source files for which automatic javadoc // generation is very difficult to do meaningfully. "-edu.wpi.first.units.measure", true) @@ -213,6 +215,7 @@ task generateJavaDocs(type: Javadoc) { dependsOn project(':wpilibj').generateJavaVersion source project(':apriltag').sourceSets.main.java source project(':cameraserver').sourceSets.main.java + source project(':commandsv3').sourceSets.main.java source project(':cscore').sourceSets.main.java source project(':epilogue-runtime').sourceSets.main.java source project(':hal').sourceSets.main.java From a5a14af3755551f590e31938358ce4a6dbcdd603 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 23 Aug 2025 12:07:57 -0400 Subject: [PATCH 102/153] Documentation pass Move SchedulerEvent convenience factories into Scheduler (no need for them to be public and documented) --- .../java/org/wpilib/commands3/Command.java | 29 +++++-- .../org/wpilib/commands3/Continuation.java | 9 +-- .../wpilib/commands3/ContinuationScope.java | 1 + .../java/org/wpilib/commands3/Mechanism.java | 8 ++ .../org/wpilib/commands3/ParallelGroup.java | 5 ++ .../commands3/ParallelGroupBuilder.java | 11 ++- .../java/org/wpilib/commands3/Scheduler.java | 77 ++++++++++++++++--- .../org/wpilib/commands3/SchedulerEvent.java | 28 ------- .../org/wpilib/commands3/SequenceBuilder.java | 13 +++- .../commands3/StagedCommandBuilder.java | 7 ++ .../org/wpilib/commands3/WaitCommand.java | 7 ++ .../commands3/button/CommandGenericHID.java | 6 ++ .../commands3/proto/SchedulerProto.java | 6 ++ 13 files changed, 149 insertions(+), 58 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 903bbea0001..7869cc42cac 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -12,11 +12,25 @@ import java.util.function.Consumer; /** - * Performs some task using one or more {@link Mechanism mechanisms} using the collaborative - * concurrency tools added in Java 21; namely, continuations. Continuations allow commands to be - * executed concurrently in a collaborative manner as coroutines; instead of needing to split - * command behavior into distinct functions (initialize(), execute(), end(), and isFinished()), - * commands can be implemented with a single, imperative loop. + * Performs some task using one or more {@link Mechanism mechanisms}. Commands are fundamentally + * backed by a {@link Coroutine} that can be used to write normal-looking code that runs + * asynchronously. + * + *

    Programmers familiar with the earlier versions of the command framework can think of a v3 + * command similar to a v1 or v2 command that executes the lifecycle methods in a single method. + * (Note, however, that more complex logic can be written than only what the v1 and v2 frameworks + * allowed for!) + * + *

    {@code
    + * coroutine -> {
    + *   initialize();
    + *   while (!isFinished()) {
    + *     execute();
    + *     coroutine.yield(); // be sure to yield at the end of the loop
    + *   }
    + *   end();
    + * }
    + * }
    * *

    Note: Because coroutines are opt-in collaborate constructs, every * command implementation must call {@link Coroutine#yield()} within any periodic @@ -259,9 +273,8 @@ static SequenceBuilder sequence(Command... commands) { } /** - * Starts creating a command that simply waits for some condition to be met. The command will - * start without any requirements, but some may be added (if necessary) using {@link - * StagedCommandBuilder#requiring(Mechanism)}. + * Starts creating a command that simply waits for some condition to be met. The command will not + * require any mechanisms. * * @param condition The condition to wait for * @return A command builder diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 2583c12bb38..e0b71b8f511 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -12,11 +12,10 @@ /** * A wrapper around the JDK internal Continuation class. Continuations are one-shot (i.e., not * reusable after completion) and allow stack frames to be paused and resumed at a later time. They - * are the underpinning for {@link VirtualThread virtual threads}, which have their own scheduler - * and JVM support. Bare continuations are designed for internal use by the JVM; we have forcibly - * opened access to them for use by the commands framework due to limitations of virtual threads; - * notably, their complete lack of determinism and timing, which are critically important for - * real-time systems like robots. + * are the underpinning for virtual threads, which have their own scheduler and JVM support. Bare + * continuations are designed for internal use by the JVM; we have forcibly opened access to them + * for use by the commands framework due to limitations of virtual threads; notably, their complete + * lack of determinism and timing, which are critically important for real-time systems like robots. * *

    ONLY USE CONTINUATIONS IN A SINGLE THREADED CONTEXT. The JVM and JIT * compilers make fundamental assumptions about how continuations are used, and rely on the code diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index cd45d20c61b..3cc46ea19c5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -9,6 +9,7 @@ import java.lang.invoke.MethodType; import java.util.Objects; +/** A continuation scope. */ public final class ContinuationScope { // The underlying jdk.internal.vm.ContinuationScope object final Object m_continuationScope; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index 0999f03e6fc..46117b13e31 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -143,6 +143,14 @@ public Command idle(Time duration) { return idle().withTimeout(duration); } + /** + * Gets all running commands that require this mechanism. Commands are returned in the order in + * which they were scheduled. The returned list is read-only. Every command in the list will have + * been scheduled by the previous entry in the list or by intermediate commands that do not + * require the mechanism. + * + * @return The currently running commands that require the mechanism. + */ public List getRunningCommands() { return m_registeredScheduler.getRunningCommandsFor(this); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 7379172a96b..36b7af97d34 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -137,6 +137,11 @@ public String toString() { return "ParallelGroup[name=" + m_name + "]"; } + /** + * Creates a new parallel group builder with no commands or configurations applied. + * + * @return A new builder. + */ public static ParallelGroupBuilder builder() { return new ParallelGroupBuilder(); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 58e01c07a2f..0e8f4a2be8e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -12,14 +12,21 @@ /** * A builder class to configure and then create a {@link ParallelGroup}. Like {@link - * CommandBuilder}, the final command is created by calling the terminal {@link #named(String)} - * method, or with an automatically generated name using {@link #withAutomaticName()}. + * StagedCommandBuilder}, the final command is created by calling the terminal {@link + * #named(String)} method, or with an automatically generated name using {@link + * #withAutomaticName()}. */ public class ParallelGroupBuilder { private final Set m_commands = new LinkedHashSet<>(); private final Set m_requiredCommands = new LinkedHashSet<>(); private BooleanSupplier m_endCondition; + /** + * Creates a new parallel group builder. The builder will have no commands and have no preapplied + * configuration options. + */ + public ParallelGroupBuilder() {} + /** * Adds one or more optional commands to the group. They will not be required to complete for the * parallel group to exit, and will be canceled once all required commands have finished. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 8cece3ace79..b3007384ffd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -24,6 +24,7 @@ import java.util.Stack; import java.util.function.Consumer; import java.util.stream.Collectors; +import org.wpilib.commands3.button.CommandGenericHID; import org.wpilib.commands3.proto.SchedulerProto; /** @@ -116,7 +117,9 @@ public class Scheduler implements ProtobufSerializable { private final ContinuationScope m_scope = new ContinuationScope("coroutine commands"); // Telemetry + /** Protobuf serializer for a scheduler. */ public static final SchedulerProto proto = new SchedulerProto(); + private double m_lastRunTimeMs = -1; private final Set> m_eventListeners = new LinkedHashSet<>(); @@ -136,6 +139,13 @@ public static Scheduler getDefault() { return s_defaultScheduler; } + /** + * Creates a new scheduler object. Note that most built-in constructs like {@link Trigger} and + * {@link CommandGenericHID} will use the {@link #getDefault() default scheduler instance} unless + * they were explicitly constructed with a different scheduler instance. Teams should use the + * default instance for convenience; however, new scheduler instances can be useful for unit + * tests. + */ public Scheduler() {} /** @@ -217,6 +227,7 @@ public void addPeriodic(Runnable callback) { }); } + /** Represents possible results of a command scheduling attempt. */ public enum ScheduleResult { /** The command was successfully scheduled and added to the queue. */ SUCCESS, @@ -244,6 +255,7 @@ public enum ScheduleResult { * than the command that forked it. * * @param command the command to schedule + * @return the result of the scheduling attempt. See {@link ScheduleResult} for details. * @throws IllegalArgumentException if scheduled by a command composition that has already * scheduled another command that shares at least one required mechanism */ @@ -296,7 +308,7 @@ ScheduleResult schedule(Binding binding) { : currentCommand(); var state = new CommandState(command, parent, buildCoroutine(command), binding); - emitEvent(SchedulerEvent.scheduled(command)); + emitEvent(scheduled(command)); if (currentState() != null) { // Scheduling a child command while running. Start it immediately instead of waiting a full @@ -355,7 +367,7 @@ private void evictConflictingOnDeckCommands(Command command) { // We don't need to call removeOrphanedChildren here because it hasn't started yet, // meaning it hasn't had a chance to schedule any children iterator.remove(); - emitEvent(SchedulerEvent.interrupted(scheduledCommand, command)); + emitEvent(interrupted(scheduledCommand, command)); } } } @@ -387,7 +399,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { // Cancel the root commands for (var conflictingState : conflictingRootStates) { - emitEvent(SchedulerEvent.interrupted(conflictingState.command(), incomingState.command())); + emitEvent(interrupted(conflictingState.command(), incomingState.command())); cancel(conflictingState.command()); } } @@ -442,7 +454,7 @@ public void cancel(Command command) { // Only run the hook if the command was running. If it was on deck or not // even in the scheduler at the time, then there's nothing to do command.onCancel(); - emitEvent(SchedulerEvent.evicted(command)); + emitEvent(evicted(command)); } // Clean up any orphaned child commands; their lifespan must not exceed the parent's @@ -531,7 +543,7 @@ private void runCommand(CommandState state) { m_executingCommands.push(state); long startMicros = RobotController.getTime(); - emitEvent(SchedulerEvent.mounted(command)); + emitEvent(mounted(command)); coroutine.mount(); try { coroutine.runToYieldPoint(); @@ -539,7 +551,7 @@ private void runCommand(CommandState state) { // Intercept the exception, inject stack frames from the schedule site, and rethrow it var binding = state.binding(); e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); - emitEvent(SchedulerEvent.completedWithError(command, e)); + emitEvent(completedWithError(command, e)); throw e; } finally { long endMicros = RobotController.getTime(); @@ -562,12 +574,12 @@ private void runCommand(CommandState state) { if (coroutine.isDone()) { // Immediately check if the command has completed and remove any children commands. // This prevents child commands from being executed one extra time in the run() loop - emitEvent(SchedulerEvent.completed(command)); + emitEvent(completed(command)); m_commandStates.remove(command); removeOrphanedChildren(command); } else { // Yielded - emitEvent(SchedulerEvent.yielded(command)); + emitEvent(yielded(command)); } } @@ -702,13 +714,13 @@ public void cancelAll() { for (var onDeckIter = m_onDeck.iterator(); onDeckIter.hasNext(); ) { var state = onDeckIter.next(); onDeckIter.remove(); - emitEvent(SchedulerEvent.evicted(state.command())); + emitEvent(evicted(state.command())); } for (var liveIter = m_commandStates.entrySet().iterator(); liveIter.hasNext(); ) { var entry = liveIter.next(); liveIter.remove(); - emitEvent(SchedulerEvent.evicted(entry.getKey())); + emitEvent(evicted(entry.getKey())); } } @@ -724,12 +736,22 @@ public EventLoop getDefaultEventLoop() { return m_eventLoop; } - /** For internal use. */ + /** + * For internal use. + * + * @return The commands that have been scheduled but not yet started. + */ public Collection getQueuedCommands() { return m_onDeck.stream().map(CommandState::command).toList(); } - /** For internal use. */ + /** + * For internal use. + * + * @param command The command to check + * @return The command that forked the provided command. Null if the command is not a child of + * another command. + */ public Command getParentOf(Command command) { var state = m_commandStates.get(command); if (state == null) { @@ -802,6 +824,37 @@ public double lastRuntimeMs() { return m_lastRunTimeMs; } + // Event-base telemetry and helpers. The static factories are for convenience to automatically + // set the timestamp instead of littering RobotController.getTime() everywhere. + + private static SchedulerEvent scheduled(Command command) { + return new SchedulerEvent.Scheduled(command, RobotController.getTime()); + } + + private static SchedulerEvent mounted(Command command) { + return new SchedulerEvent.Mounted(command, RobotController.getTime()); + } + + private static SchedulerEvent yielded(Command command) { + return new SchedulerEvent.Yielded(command, RobotController.getTime()); + } + + private static SchedulerEvent completed(Command command) { + return new SchedulerEvent.Completed(command, RobotController.getTime()); + } + + private static SchedulerEvent completedWithError(Command command, Throwable error) { + return new SchedulerEvent.CompletedWithError(command, error, RobotController.getTime()); + } + + private static SchedulerEvent evicted(Command command) { + return new SchedulerEvent.Evicted(command, RobotController.getTime()); + } + + private static SchedulerEvent interrupted(Command command, Command interrupter) { + return new SchedulerEvent.Interrupted(command, interrupter, RobotController.getTime()); + } + /** * Adds a listener to handle events that are emitted by the scheduler. Events are emitted when * certain actions are taken by user code or by internal processing logic in the scheduler. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index 151ff3805bf..603a691b0fb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -24,34 +24,6 @@ public sealed interface SchedulerEvent { */ long timestampMicros(); - static SchedulerEvent scheduled(Command command) { - return new Scheduled(command, RobotController.getTime()); - } - - static SchedulerEvent mounted(Command command) { - return new Mounted(command, RobotController.getTime()); - } - - static SchedulerEvent yielded(Command command) { - return new Yielded(command, RobotController.getTime()); - } - - static SchedulerEvent completed(Command command) { - return new Completed(command, RobotController.getTime()); - } - - static SchedulerEvent completedWithError(Command command, Throwable error) { - return new CompletedWithError(command, error, RobotController.getTime()); - } - - static SchedulerEvent evicted(Command command) { - return new Evicted(command, RobotController.getTime()); - } - - static SchedulerEvent interrupted(Command command, Command interrupter) { - return new Interrupted(command, interrupter, RobotController.getTime()); - } - /** * An event marking when a command is scheduled in {@link Scheduler#schedule(Command)}. * diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index 64949648484..26815eb71b5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -12,14 +12,21 @@ import java.util.stream.Collectors; /** - * A builder class to configure and then create a {@link Sequence}. Like {@link CommandBuilder}, the - * final command is created by calling the terminal {@link #named(String)} method, or with an - * automatically generated name using {@link #withAutomaticName()}. + * A builder class to configure and then create a {@link Sequence}. Like {@link + * StagedCommandBuilder}, the final command is created by calling the terminal {@link + * #named(String)} method, or with an automatically generated name using {@link + * #withAutomaticName()}. */ public class SequenceBuilder { private final List m_steps = new ArrayList<>(); private BooleanSupplier m_endCondition; + /** + * Creates new SequenceBuilder. The builder will have no commands and have no preapplied + * configuration options. Use {@link #andThen(Command)} to add commands to the sequence. + */ + public SequenceBuilder() {} + /** * Adds a command to the sequence. * diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java index 7a8d195fd54..ed4cbc6138b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java @@ -216,6 +216,13 @@ public String toString() { } } + /** + * Creates a new command builder. All required options must be set on each stage before a command + * is able to be created. Attempting to create a command without setting all required options will + * result in a compilation error. + */ + public StagedCommandBuilder() {} + /** * Explicitly marks the command as requiring no mechanisms. Unless overridden later with {@link * NeedsExecutionBuilderStage#requiring(Mechanism)} or a similar method, the built command will diff --git a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java index 0445a4b43d8..a51641f89fb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java @@ -15,6 +15,12 @@ public class WaitCommand implements Command { private final Time m_duration; + /** + * Creates a new WaitCommand. The command will wait for the given duration of time before + * completing. + * + * @param duration How long to wait for. + */ public WaitCommand(Time duration) { m_duration = requireNonNullParam(duration, "duration", "WaitCommand"); } @@ -30,6 +36,7 @@ public void run(Coroutine coroutine) { @Override public String name() { + // Normalize to seconds so all wait commands have the same name format return "Wait " + m_duration.in(Seconds) + " Seconds"; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java index 809173f345d..1e13b8178db 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java @@ -337,6 +337,12 @@ public boolean isConnected() { return m_hid.isConnected(); } + /** + * Gets the scheduler that should execute the triggered commands. This scheduler is set in the + * constructor, defaulting to {@link Scheduler#getDefault()} if one was not provided. + * + * @return the scheduler that should execute the triggered commands + */ protected final Scheduler getScheduler() { return m_scheduler; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java index e61e136cb96..5f93ecc7dd0 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java @@ -8,6 +8,12 @@ import org.wpilib.commands3.Scheduler; import us.hebi.quickbuf.Descriptors; +/** + * Serializes a {@link Scheduler} to a protobuf message. Deserialization is not supported. A + * serialized message will include information about commands that are currently running or + * scheduled (but not yet started), as well as how long the most recent call to {@link + * Scheduler#run()} took to execute. + */ public class SchedulerProto implements Protobuf { @Override public Class getTypeClass() { From 0f7d40b2dfdc4c9f71d4a2ec09f3ad392b0e4a99 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 23 Aug 2025 14:00:20 -0400 Subject: [PATCH 103/153] Lint --- commandsv3/src/main/java/org/wpilib/commands3/CommandState.java | 1 + docs/BUILD.bazel | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index 66fac4d599e..bb8227dfcdc 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -7,6 +7,7 @@ /** Represents the state of a command as it is executed by the scheduler. */ final class CommandState { // Two billion unique IDs should be enough for anybody. + @SuppressWarnings("PMD.RedundantFieldInitializer") // we're explicitly counting up from zero private static int s_lastId = 0; private final Command m_command; diff --git a/docs/BUILD.bazel b/docs/BUILD.bazel index e10c2d553bf..06f5acdcee2 100644 --- a/docs/BUILD.bazel +++ b/docs/BUILD.bazel @@ -106,8 +106,8 @@ javadoc( deps = [ "//apriltag:apriltag-java", "//cameraserver:cameraserver-java", - "//cscore:cscore-java", "//commandsv3:commandsv3-java", + "//cscore:cscore-java", "//epilogue-runtime:epilogue-java", "//hal:hal-java", "//ntcore:ntcore-java", From 0c2d420688baa6f2173dc092a8ae8f13561358e3 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 26 Aug 2025 21:52:35 -0400 Subject: [PATCH 104/153] Run child commands BEFORE parents, not after This removes a 1-loop cycle penalty for parents to resume after a child completes. The penalty was caused by the parent checking if the child completed /before/ the child ran, so the first time a parent would have been able to resume would be the loop immediately after the child completed. Actual command ordering is unchanged (eg ordering in telemetry is still [parent, child]) --- .../java/org/wpilib/commands3/Scheduler.java | 5 +- .../wpilib/commands3/ParallelGroupTest.java | 20 +-- .../org/wpilib/commands3/SchedulerTest.java | 121 +++++++++++++++++- .../org/wpilib/commands3/SequenceTest.java | 30 +---- .../org/wpilib/commands3/TriggerTest.java | 6 +- 5 files changed, 136 insertions(+), 46 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index b3007384ffd..7e0e406671e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -519,7 +519,10 @@ private void runPeriodicSideloads() { private void runCommands() { // Tick every command that hasn't been completed yet - for (var state : List.copyOf(m_commandStates.values())) { + // Run in reverse so parent commands can resume in the same loop cycle an awaited child command + // completes. Otherwise, parents could only resume on the next loop cycle, introducing a delay + // at every layer of nesting. + for (var state : List.copyOf(m_commandStates.values()).reversed()) { runCommand(state); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 1a6e09af7d3..ff3463370d0 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -131,12 +131,8 @@ void race() { assertEquals(i, c2Count.get()); } m_scheduler.run(); // complete c1 - assertTrue(m_scheduler.isRunning(race)); - assertFalse(m_scheduler.isRunning(c1)); - assertTrue(m_scheduler.isRunning(c2)); - - m_scheduler.run(); // complete parallel and cleanup assertFalse(m_scheduler.isRunning(race)); + assertFalse(m_scheduler.isRunning(c1)); assertFalse(m_scheduler.isRunning(c2)); // and final counts should be 5 and 5 @@ -188,20 +184,8 @@ void nested() { // Run 6: Command should have completed naturally m_scheduler.run(); - assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); - assertTrue(m_scheduler.isRunning(inner), "Inner group should be running"); - assertFalse(m_scheduler.isRunning(command), "Command should have completed"); - - // Run 7: Having seen the command complete, inner group should exit - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(outer), "Outer group should be running"); - assertFalse(m_scheduler.isRunning(inner), "Inner group should have completed"); - assertFalse(m_scheduler.isRunning(command), "Command should have completed"); - - // Run 8: Having seen the inner group complete, outer group should now exit - m_scheduler.run(); assertFalse(m_scheduler.isRunning(outer), "Outer group should be running"); - assertFalse(m_scheduler.isRunning(inner), "Inner group should have completed"); + assertFalse(m_scheduler.isRunning(inner), "Inner group should be running"); assertFalse(m_scheduler.isRunning(command), "Command should have completed"); } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 0ed616f9053..43497f1e6cb 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -4,6 +4,9 @@ package org.wpilib.commands3; +import static edu.wpi.first.units.Units.Microseconds; +import static edu.wpi.first.units.Units.Milliseconds; +import static edu.wpi.first.units.Units.Seconds; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertInstanceOf; @@ -18,6 +21,7 @@ import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicLong; import java.util.concurrent.atomic.AtomicReference; import java.util.function.Supplier; import org.junit.jupiter.api.BeforeEach; @@ -249,7 +253,7 @@ void nestedErrorDetection() { @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs - void runmechanism() { + void runMechanism() { var example = new Mechanism("Counting", m_scheduler) { int m_x = 0; @@ -643,7 +647,7 @@ void sideloadThrowingException() { } @Test - void nestedmechanisms() { + void nestedMechanisms() { var superstructure = new Mechanism("Superstructure", m_scheduler) { private final Mechanism m_elevator = new Mechanism("Elevator", m_scheduler); @@ -949,6 +953,119 @@ void commandDeadlock() { assertFalse(m_scheduler.isRunning(command2)); } + @Test + void forkedChildRunsOnce() { + AtomicInteger runCount = new AtomicInteger(0); + + var inner = + Command.noRequirements() + .executing( + co -> { + runCount.incrementAndGet(); + co.yield(); + + runCount.incrementAndGet(); + co.yield(); + }) + .named("Inner"); + + var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); + m_scheduler.schedule(outer); + m_scheduler.run(); + + assertEquals(1, runCount.get()); + } + + @Test + void shortWaitWaitsOneLoop() { + AtomicLong time = new AtomicLong(0); + RobotController.setTimeSource(time::get); + + AtomicBoolean completedWait = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing( + co -> { + co.wait(Milliseconds.of(1)); + completedWait.set(true); + }) + .named("Short Wait"); + + m_scheduler.schedule(command); + m_scheduler.run(); + + // wait 1 full second (much longer than the wait period) + time.set((long) Seconds.of(1).in(Microseconds)); + m_scheduler.run(); + assertTrue( + completedWait.get(), + "Command with a short wait should have completed if its duration has elapsed between runs"); + } + + @Test + void shortWaitWaitsOneLoopWithFastPeriod() { + AtomicLong time = new AtomicLong(0); + RobotController.setTimeSource(time::get); + AtomicBoolean completedWait = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing( + co -> { + co.wait(Milliseconds.of(1)); + completedWait.set(true); + }) + .named("Short Wait"); + + m_scheduler.schedule(command); + m_scheduler.run(); + + // move forward by half the wait period + time.set((long) Milliseconds.of(0.5).in(Microseconds)); + m_scheduler.run(); + assertFalse(completedWait.get(), "Command should still be waiting for 1 ms to elapse"); + + // move forward by the rest of the wait period + time.set((long) Milliseconds.of(1).in(Microseconds)); + m_scheduler.run(); + assertTrue( + completedWait.get(), + "Command with a short wait should have completed if its duration has elapsed between runs"); + } + + @Test + void awaitingExitsImmediatelyWithoutAOneLoopDelay() { + AtomicInteger innerRuns = new AtomicInteger(0); + var inner = + Command.noRequirements() + .executing( + co -> { + // executed immediately when forked + innerRuns.incrementAndGet(); + co.yield(); + + // executed again on the next scheduler run, after the forking command runs + innerRuns.incrementAndGet(); + }) + .named("Inner"); + + var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); + m_scheduler.schedule(outer); // schedules inner + + // First run: runs outer, forks inner, inner runs to its first yield, outer yields + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(inner)); + assertTrue(m_scheduler.isRunning(outer)); + assertEquals(1, innerRuns.get()); + + // Second run: runs inner to completion, runs outer, outer sees inner is complete and exits + // NOTE: If child commands ran AFTER their parents, then outer would not have exited here and + // would take another scheduler run to complete + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(inner)); + assertFalse(m_scheduler.isRunning(outer)); + assertEquals(2, innerRuns.get()); + } + record PriorityCommand(int priority, Mechanism... subsystems) implements Command { @Override public void run(Coroutine coroutine) { diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java index 97aac7680f5..01f5e0d180c 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java @@ -26,17 +26,12 @@ void single() { var sequence = new Sequence("The Sequence", List.of(command)); m_scheduler.schedule(sequence); - // First run - the composed command is scheduled and starts + // First run - the composed command starts and yields; sequence yields m_scheduler.run(); assertTrue(m_scheduler.isRunning(sequence)); assertTrue(m_scheduler.isRunning(command)); - // Second run - the composed command completes - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(sequence)); - assertFalse(m_scheduler.isRunning(command)); - - // Third run - sequence sees the composed command is done and completes + // Second run - the composed command completes; sequence sees its completion and exits m_scheduler.run(); assertFalse(m_scheduler.isRunning(sequence)); assertFalse(m_scheduler.isRunning(command)); @@ -58,27 +53,16 @@ void twoCommands() { m_scheduler.isScheduledOrRunning(c2), "The second command should still be pending completion of the first command"); - // Second run - c1 completes + // Second run - c1 completes, sequence sees it finish, schedules c2 m_scheduler.run(); assertTrue(m_scheduler.isRunning(sequence)); assertFalse(m_scheduler.isRunning(c1), "First command should have completed"); - assertFalse( + assertTrue( m_scheduler.isScheduledOrRunning(c2), "Second command should not start in the same cycle"); - // Third run - c2 is scheduled and starts - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(sequence)); - assertTrue(m_scheduler.isRunning(c2), "Second command should have started"); - - // Fourth run - c2 completes - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(sequence)); - assertFalse(m_scheduler.isRunning(c2), "Second command should have completed"); - - // Fifth run - sequence completes + // Third run - c2 completes, sequence sees it finish, exits m_scheduler.run(); - assertFalse(m_scheduler.isRunning(sequence), "Sequence should have completed"); - assertFalse(m_scheduler.isRunning(c1), "First command should have stopped"); - assertFalse(m_scheduler.isRunning(c2), "Second command should have stopped"); + assertFalse(m_scheduler.isRunning(sequence)); + assertFalse(m_scheduler.isRunning(c2), "Second command should have started"); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index f4db4675f0f..df027a22d4e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -235,13 +235,15 @@ void triggerFromExitingCommandDoesNotFire() { m_scheduler.run(); assertTrue(m_scheduler.isRunning(outer)); assertTrue(m_scheduler.isRunning(awaited)); + assertEquals( + List.of("Outer", "Awaited"), + m_scheduler.getRunningCommands().stream().map(Command::name).toList()); // Second run: `awaited` resumes, sets the condition, exits. `outer` exits its final `yield` // and will exit on the next run. The trigger condition has been set, but the trigger is checked // on the next call to `run()` m_scheduler.run(); - assertEquals( - List.of("Outer"), m_scheduler.getRunningCommands().stream().map(Command::name).toList()); + assertEquals(List.of(), m_scheduler.getRunningCommands().stream().map(Command::name).toList()); assertTrue(condition.get(), "Condition wasn't set"); assertFalse(triggeredCommandRan.get(), "Command was unexpectedly triggered"); From 547853b948fb3e0efe952948d1d7d6b56e0c0c32 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 26 Aug 2025 22:11:26 -0400 Subject: [PATCH 105/153] Document caveats around waiting for a fixed time --- .../main/java/org/wpilib/commands3/Coroutine.java | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index d4e9ddc1a27..5cc72e8a6a8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -245,6 +245,20 @@ private static void validateNoConflicts(Collection commands) { * Waits for some duration of time to elapse. Returns immediately if the given duration is zero or * negative. Call this within a command or command composition to introduce a simple delay. * + *

    Note that the resolution of the wait period is equal to the period at which {@link + * Scheduler#run()} is called by the robot program. If using a 20 millisecond update period, the + * wait will be rounded up to the nearest 20 millisecond interval; in this scenario, calling + * {@code wait(Milliseconds.of(1))} and {@code wait(Milliseconds.of(19))} would have identical + * effects. + * + *

    Very small loop times near the loop period are sensitive to the order in which commands are + * executed. If a command waits for 10 ms at the end of a scheduler cycle, and then all the + * commands that ran before it complete or exit, and then the next cycle starts immediately, the + * wait will be evaluated at the start of that next cycle, which occurred less than 10 ms + * later. Therefore the wait will see not enough time has passed and only exit after an additional + * cycle elapses, adding an unexpected extra 20 ms to the wait time. Note that this becomes less + * of a problem with smaller loop periods, as the extra 1-loop delay becomes smaller. + * *

    For example, a basic autonomous routine that drives straight for 5 seconds: * *

    {@code
    
    From 7185f254e882ade49e080208d0fa642e7a19dff8 Mon Sep 17 00:00:00 2001
    From: Sam Carlberg 
    Date: Sat, 30 Aug 2025 22:28:34 -0400
    Subject: [PATCH 106/153] Documentation and API cleanup pass
    
    Make any javadoc and internal documentation comments clearer
    
    Add consistent null checks across the public API surface
    
    Refactor scheduler event methods to have better names
    
    Remove internal use of Sequence.* and ParallelGroup.* factory methods, preferring to use builder objects directly
    
    Add links to Continuation and ContinuationScope source code
    
    Add Continuation.forkAll for easier use by parallel groups
    
    Refactor ParallelGroup to store optional and required commands separately (as two distinct sets), instead of implicitly tracking optional commands as those included in `allCommands` but not `requiredCommands`
    ---
     .../java/org/wpilib/commands3/Command.java    | 127 +++++++----
     .../org/wpilib/commands3/CommandState.java    |  11 +-
     .../org/wpilib/commands3/Continuation.java    |  31 ++-
     .../wpilib/commands3/ContinuationScope.java   |   1 +
     .../java/org/wpilib/commands3/Coroutine.java  | 107 +++++++--
     .../org/wpilib/commands3/ParallelGroup.java   |  55 ++---
     .../commands3/ParallelGroupBuilder.java       |  16 +-
     .../java/org/wpilib/commands3/Scheduler.java  | 209 +++++++++---------
     .../java/org/wpilib/commands3/Sequence.java   |  14 +-
     .../org/wpilib/commands3/SequenceBuilder.java |  20 +-
     .../java/org/wpilib/commands3/Trigger.java    |   6 +-
     .../wpilib/commands3/ParallelGroupTest.java   |   5 +-
     12 files changed, 395 insertions(+), 207 deletions(-)
    
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java
    index 7869cc42cac..a57d3f33ee0 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java
    @@ -4,6 +4,8 @@
     
     package org.wpilib.commands3;
     
    +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
    +
     import edu.wpi.first.units.measure.Time;
     import java.util.Collection;
     import java.util.Collections;
    @@ -13,13 +15,12 @@
     
     /**
      * Performs some task using one or more {@link Mechanism mechanisms}. Commands are fundamentally
    - * backed by a {@link Coroutine} that can be used to write normal-looking code that runs
    - * asynchronously.
    + * backed by a {@link Coroutine} that can be used to write imperative code that runs asynchronously.
      *
      * 

    Programmers familiar with the earlier versions of the command framework can think of a v3 - * command similar to a v1 or v2 command that executes the lifecycle methods in a single method. - * (Note, however, that more complex logic can be written than only what the v1 and v2 frameworks - * allowed for!) + * command similar to a v1 or v2 command that executes the lifecycle methods in a single method, as + * demonstrated in the example below. (Note, however, that more sophisticated code than this is + * possible! * *

    {@code
      * coroutine -> {
    @@ -51,7 +52,7 @@
      * of fundamental building blocks. These built-in compositions will require every mechanism used by
      * every command in them, even if those commands aren't always running, and thus can leave certain
      * required mechanisms in an uncommanded state: owned, but not used, this can lead to
    - * mechanisms sagging under gravity or running the motor control request they were given.
    + * mechanisms sagging under gravity or running the previous motor control request they were given.
      *
      * 

    Advanced Usage

    * @@ -82,10 +83,10 @@ * // to run when not in use. Interrupting one of the inner commands while it's * // running will cancel the entire sequence. * private Command advancedScoringSequence() { - * return Command.noRequirements().executing(co -> { - * co.await(drivetrain.driveToScoringLocation()); - * co.await(elevator.moveToScoringHeight()); - * co.await(gripper.release()); + * return Command.noRequirements().executing(coroutine -> { + * coroutine.await(drivetrain.driveToScoringLocation()); + * coroutine.await(elevator.moveToScoringHeight()); + * coroutine.await(gripper.release()); * }).named("Scoring Sequence (Advanced)"); * } * } @@ -109,7 +110,8 @@ public interface Command { /** * Runs the command. Commands that need to periodically run until a goal state is reached should - * simply run a while loop like {@code while (!atGoal() && coroutine.yield()) { ... } }. + * simply run a while loop like {@code while (!atGoal()) { ... } } and call {@link + * Coroutine#yield()} at the end of the loop. * *

    Warning: any loops in a command must call {@code coroutine.yield()}. * Failure to do so will prevent anything else in your robot code from running. Commands are @@ -137,8 +139,8 @@ default void onCancel() { /** * The mechanisms required by the command. This is used by the scheduler to determine if two - * commands conflict with each other. Any singular mechanism may only be required by a single - * running command at a time. + * commands conflict with each other. No mechanism may be required by more than one running + * command at a time. * * @return the set of mechanisms required by the command */ @@ -146,10 +148,10 @@ default void onCancel() { /** * The priority of the command. If a command is scheduled that conflicts with another running or - * pending command, the relative priority values are compared. If the scheduled command is lower - * priority than the running command, then it will not be scheduled and the running command will - * continue to run. If it is the same or higher priority, then the running command will be - * canceled and the scheduled command will start to run. + * pending command, their priority values are compared to determine which should run. If the + * scheduled command is lower priority than the running command, then it will not be scheduled and + * the running command will continue to run. If it is the same or higher priority, then the + * running command will be canceled and the scheduled command will start to run. * * @return the priority of the command */ @@ -164,14 +166,16 @@ default int priority() { * @return true if this command has a lower priority than the other one, false otherwise */ default boolean isLowerPriorityThan(Command other) { - return other != null && priority() < other.priority(); + requireNonNullParam(other, "other", "Command.isLowerPriorityThan"); + + return priority() < other.priority(); } /** * Checks if this command requires a particular mechanism. * * @param mechanism the mechanism to check - * @return true if the mechanism is a member of the required mechanisms, false if not + * @return true if the mechanism is required, false if not */ default boolean requires(Mechanism mechanism) { return requirements().contains(mechanism); @@ -185,6 +189,8 @@ default boolean requires(Mechanism mechanism) { * commands have completely different requirements */ default boolean conflictsWith(Command other) { + requireNonNullParam(other, "other", "Command.conflictsWith"); + return !Collections.disjoint(requirements(), other.requirements()); } @@ -193,22 +199,28 @@ default boolean conflictsWith(Command other) { * canceled. This is particularly useful for autonomous routines where you want to prevent your * entire autonomous period spent stuck on a single action because a mechanism doesn't quite reach * its setpoint (for example, spinning up a flywheel or driving to a particular location on the - * field). The resulting command will have the same name as this one. + * field). The resulting command will have the same name as this one, with the timeout period + * appended. * * @param timeout the maximum duration that the command is permitted to run. Negative or zero * values will result in the command running only once before being canceled. * @return the timed out command. */ default Command withTimeout(Time timeout) { - return ParallelGroup.race(this, new WaitCommand(timeout)) + requireNonNullParam(timeout, "timeout", "Command.withTimeout"); + + return race(this, new WaitCommand(timeout)) .named(name() + " [" + timeout.toLongString() + " timeout]"); } /** * Creates a command that does not require any hardware; that is, it does not affect the state of - * any physical objects. This is useful for commands that do some house cleaning work like - * resetting odometry and sensors that you don't want to interrupt a command that's controlling - * the mechanisms it affects. + * any physical objects. This is useful for commands that do some cleanup or state management, + * such as resetting odometry or sensors, that you don't want to interrupt a command that's + * controlling the mechanisms it affects. + * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link StagedCommandBuilder} for details. * * @return a builder that can be used to configure the resulting command */ @@ -217,23 +229,31 @@ static NeedsExecutionBuilderStage noRequirements() { } /** - * Starts creating a command that requires one or more mechanisms. + * Creates a command that requires one or more mechanisms. + * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link StagedCommandBuilder} for details. * * @param requirement The first required mechanism * @param rest Any other required mechanisms * @return A command builder */ static NeedsExecutionBuilderStage requiring(Mechanism requirement, Mechanism... rest) { + // parameters will be null checked by the builder return new StagedCommandBuilder().requiring(requirement, rest); } /** - * Starts creating a command that requires some number of mechanisms. + * Creates command that requires some number of mechanisms. + * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link StagedCommandBuilder} for details. * * @param requirements The required mechanisms. May be empty, but cannot contain null values. * @return A command builder */ static NeedsExecutionBuilderStage requiring(Collection requirements) { + // parameters will be null checked by the builder return new StagedCommandBuilder().requiring(requirements); } @@ -241,11 +261,15 @@ static NeedsExecutionBuilderStage requiring(Collection requirements) * Starts creating a command that runs a group of multiple commands in parallel. The command will * complete when every command in the group has completed naturally. * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link ParallelGroupBuilder} for details. + * * @param commands The commands to run in parallel * @return A command builder */ static ParallelGroupBuilder parallel(Command... commands) { - return ParallelGroup.all(commands); + // parameters will be null checked by the builder + return new ParallelGroupBuilder().requiring(commands); } /** @@ -253,11 +277,15 @@ static ParallelGroupBuilder parallel(Command... commands) { * complete when any command in the group has completed naturally; all other commands in the group * will be canceled. * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link ParallelGroupBuilder} for details. + * * @param commands The commands to run in parallel * @return A command builder */ static ParallelGroupBuilder race(Command... commands) { - return ParallelGroup.race(commands); + // parameters will be null checked by the builder + return new ParallelGroupBuilder().optional(commands); } /** @@ -265,21 +293,30 @@ static ParallelGroupBuilder race(Command... commands) { * complete when the last command in the group has completed naturally. Commands in the group will * run in the order they're passed to this method. * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link SequenceBuilder} for details. + * * @param commands The commands to run in sequence. * @return A command builder */ static SequenceBuilder sequence(Command... commands) { - return Sequence.sequence(commands); + // parameters will be null checked by the builder + return new SequenceBuilder().andThen(commands); } /** * Starts creating a command that simply waits for some condition to be met. The command will not * require any mechanisms. * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link StagedCommandBuilder} for details. + * * @param condition The condition to wait for * @return A command builder */ static NeedsNameBuilderStage waitUntil(BooleanSupplier condition) { + requireNonNullParam(condition, "condition", "Command.waitUntil"); + return noRequirements().executing(coroutine -> coroutine.waitUntil(condition)); } @@ -287,17 +324,22 @@ static NeedsNameBuilderStage waitUntil(BooleanSupplier condition) { * Creates a command that runs this one and ends when the end condition is met (if this command * has not already exited by then). * + *

    More configuration options are needed after calling this function before the command can be + * created. See {@link ParallelGroupBuilder} for details. + * * @param endCondition The end condition to wait for. * @return The waiting command */ default ParallelGroupBuilder until(BooleanSupplier endCondition) { - return ParallelGroup.builder() + requireNonNullParam(endCondition, "endCondition", "Command.until"); + + return new ParallelGroupBuilder() .optional(this, Command.waitUntil(endCondition).named("Until Condition")); } /** - * Starts creating a command sequence, starting from this command and then running the next one. - * More commands can be added with the builder before naming and creating the sequence. + * Creates a command sequence, starting from this command and then running the next one. More + * commands can be added with the builder before naming and creating the sequence. * *

    {@code
        * Sequence aThenBThenC =
    @@ -311,12 +353,16 @@ default ParallelGroupBuilder until(BooleanSupplier endCondition) {
        * @return A sequence builder
        */
       default SequenceBuilder andThen(Command next) {
    -    return Sequence.builder().andThen(this).andThen(next);
    +    // parameter will be null checked by the builder
    +    return new SequenceBuilder().andThen(this).andThen(next);
       }
     
       /**
    -   * Starts creating a parallel command group, running this command alongside one or more other
    -   * commands. The group will exit once every command has finished.
    +   * Creates a parallel command group, running this command alongside one or more other commands.
    +   * The group will exit once every command has finished.
    +   *
    +   * 

    More configuration options are needed after calling this function before the command can be + * created. See {@link ParallelGroupBuilder} for details. * *

    {@code
        * ParallelGroup abc =
    @@ -329,17 +375,20 @@ default SequenceBuilder andThen(Command next) {
        * @return A parallel group builder
        */
       default ParallelGroupBuilder alongWith(Command... parallel) {
    -    return ParallelGroup.builder().requiring(this).requiring(parallel);
    +    return new ParallelGroupBuilder().requiring(this).requiring(parallel);
       }
     
       /**
    -   * Starts creating a parallel command group, running this command alongside one or more other
    -   * commands. The group will exit after any command finishes.
    +   * Creates a parallel command group, running this command alongside one or more other commands.
    +   * The group will exit after any command finishes.
    +   *
    +   * 

    More configuration options are needed after calling this function before the command can be + * created. See {@link ParallelGroupBuilder} for details. * * @param parallel The commands to run in parallel with this one * @return A parallel group builder */ default ParallelGroupBuilder raceWith(Command... parallel) { - return ParallelGroup.builder().optional(this).optional(parallel); + return new ParallelGroupBuilder().optional(this).optional(parallel); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index bb8227dfcdc..5d37182ae32 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -4,6 +4,8 @@ package org.wpilib.commands3; +import static java.util.Objects.requireNonNull; + /** Represents the state of a command as it is executed by the scheduler. */ final class CommandState { // Two billion unique IDs should be enough for anybody. @@ -31,10 +33,10 @@ final class CommandState { * @param binding The binding that caused the command to be scheduled. */ CommandState(Command command, Command parent, Coroutine coroutine, Binding binding) { - m_command = command; - m_parent = parent; - m_coroutine = coroutine; - m_binding = binding; + m_command = requireNonNull(command, "WPILib bug: command state given null command"); + m_parent = parent; // allowed to be null + m_coroutine = requireNonNull(coroutine, "WPILib bug: command state given null coroutine"); + m_binding = requireNonNull(binding, "WPILib bug: command state given null binding"); // This is incredibly non-thread safe, but nobody should be using the command framework across // multiple threads anyway. Worst case scenario, we'll get duplicate IDs for commands scheduled @@ -54,7 +56,6 @@ public Coroutine coroutine() { return m_coroutine; } - // may return null public Binding binding() { return m_binding; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index e0b71b8f511..425d05cb1b4 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -28,6 +28,7 @@ */ public final class Continuation { // The underlying jdk.internal.vm.Continuation object + // https://github.com/openjdk/jdk/blob/jdk-21%2B35/src/java.base/share/classes/jdk/internal/vm/Continuation.java private final Object m_continuation; static final Class jdk_internal_vm_Continuation; @@ -91,6 +92,20 @@ public final class Continuation { } } + /** + * Used to wrap any checked exceptions bubbled from when calling the internal continuation methods + * via reflection. Per the Continuation API as of Java 21, none of the methods we're calling will + * throw unchecked exceptions (IllegalState or other runtime exceptions, yes, and we bubble those + * up directly); however, the MethodHandle API's `invoke` method has `throws Throwable` in its + * signature and we have to handle it. + */ + @SuppressWarnings("PMD.DoNotExtendJavaLangError") + static final class InternalContinuationError extends Error { + InternalContinuationError(String message, Throwable cause) { + super(message, cause); + } + } + private final ContinuationScope m_scope; /** @@ -121,15 +136,17 @@ public Continuation(ContinuationScope scope, Runnable target) { public boolean yield() { try { return (boolean) YIELD.invoke(m_scope.m_continuationScope); - } catch (RuntimeException e) { + } catch (RuntimeException | Error e) { throw e; } catch (Throwable t) { - throw new Error(t); + throw new InternalContinuationError( + "Continuation.yield() encountered an unexpected error", t); } } /** - * Mounts and runs the continuation body. If suspended, continues it from the last suspend point. + * Mounts and runs the continuation body until the body calls {@link #yield()}. If the + * continuation is suspended, it will continue from the most recent yield point. */ @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) public void run() { @@ -141,7 +158,7 @@ public void run() { // The bound task threw an exception; re-throw it throw e; } catch (Throwable t) { - throw new RuntimeException(t); + throw new InternalContinuationError("Continuation.run() encountered an unexpected error", t); } } @@ -157,7 +174,8 @@ public boolean isDone() { } catch (RuntimeException | Error e) { throw e; } catch (Throwable t) { - throw new RuntimeException(t); + throw new InternalContinuationError( + "Continuation.isDone() encountered an unexpected error", t); } } @@ -185,7 +203,8 @@ public static void mountContinuation(Continuation continuation) { // It only assigns to a field, no way to throw // However, if the invocation fails for some reason, we'll end up with an // IllegalStateException when attempting to run an unmounted continuation - throw new RuntimeException(t); + throw new InternalContinuationError( + "Continuation.mountContinuation() encountered an unexpected error", t); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index 3cc46ea19c5..5e8d7c2541b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -12,6 +12,7 @@ /** A continuation scope. */ public final class ContinuationScope { // The underlying jdk.internal.vm.ContinuationScope object + // https://github.com/openjdk/jdk/blob/jdk-21%2B35/src/java.base/share/classes/jdk/internal/vm/ContinuationScope.java final Object m_continuationScope; static final Class jdk_internal_vm_ContinuationScope; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 5cc72e8a6a8..6651985986f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -4,6 +4,8 @@ package org.wpilib.commands3; +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + import edu.wpi.first.units.measure.Time; import java.util.Arrays; import java.util.Collection; @@ -49,9 +51,10 @@ public boolean yield() { return m_backingContinuation.yield(); } catch (IllegalStateException e) { if ("Pinned: MONITOR".equals(e.getMessage())) { + // Raised when a continuation yields inside a synchronized block or method: + // https://github.com/openjdk/jdk/blob/jdk-21%2B35/src/java.base/share/classes/jdk/internal/vm/Continuation.java#L396-L402 // Note: Not a thing in Java 24+ - // Yielding inside a synchronized block or method - // Throw with an error message that's more helpful for our users + // Rethrow with an error message that's more helpful for our users throw new IllegalStateException( "Coroutine.yield() cannot be called inside a synchronized block or method. " + "Consider using a Lock instead of synchronized, " @@ -106,6 +109,11 @@ public void park() { public void fork(Command... commands) { requireMounted(); + requireNonNullParam(commands, "commands", "Coroutine.fork"); + for (int i = 0; i < commands.length; i++) { + requireNonNullParam(commands[i], "commands[" + i + "]", "Coroutine.fork"); + } + // Check for user error; there's no reason to fork conflicting commands simultaneously validateNoConflicts(List.of(commands)); @@ -115,6 +123,51 @@ public void fork(Command... commands) { } } + /** + * Forks off some commands. Each command will run until its natural completion, the parent command + * exits, or the parent command cancels it. The parent command will continue executing while the + * forked commands run, and can resync with the forked commands using {@link + * #awaitAll(Collection)}. + * + *

    {@code
    +   * Command example() {
    +   *   return Command.noRequirements().executing(coroutine -> {
    +   *     Collection innerCommands = ...;
    +   *     coroutine.fork(innerCommands);
    +   *     // ... do more things
    +   *     // then sync back up with the inner commands
    +   *     coroutine.awaitAll(innerCommands);
    +   *   }).named("Example");
    +   * }
    +   * }
    + * + *

    Note: forking a command that conflicts with a higher-priority command will fail. The forked + * command will not be scheduled, and the existing command will continue to run. + * + * @param commands The commands to fork. + * @throws IllegalStateException if called anywhere other than the coroutine's running command + */ + public void forkAll(Collection commands) { + requireMounted(); + + validateNoConflicts(commands); + + requireNonNullParam(commands, "commands", "Coroutine.fork"); + int i = 0; + for (Command command : commands) { + requireNonNullParam(command, "commands[" + i + "]", "Coroutine.fork"); + i++; + } + + // Check for user error; there's no reason to fork conflicting commands simultaneously + validateNoConflicts(commands); + + // Shorthand; this is handy for user-defined compositions + for (var command : commands) { + m_scheduler.schedule(command); + } + } + /** * Awaits completion of a command. If the command is not currently scheduled or running, it will * be scheduled automatically. @@ -125,6 +178,8 @@ public void fork(Command... commands) { public void await(Command command) { requireMounted(); + requireNonNullParam(command, "command", "Coroutine.await"); + m_scheduler.schedule(command); while (m_scheduler.isScheduledOrRunning(command)) { @@ -145,6 +200,13 @@ public void await(Command command) { public void awaitAll(Collection commands) { requireMounted(); + requireNonNullParam(commands, "commands", "Coroutine.awaitAll"); + int i = 0; + for (Command command : commands) { + requireNonNullParam(command, "commands[" + i + "]", "Coroutine.awaitAll"); + i++; + } + validateNoConflicts(commands); for (var command : commands) { @@ -154,8 +216,6 @@ public void awaitAll(Collection commands) { while (commands.stream().anyMatch(m_scheduler::isScheduledOrRunning)) { this.yield(); } - - // The scheduler will clean up anything that's still running at this point } /** @@ -181,6 +241,13 @@ public void awaitAll(Command... commands) { public void awaitAny(Collection commands) { requireMounted(); + requireNonNullParam(commands, "commands", "Coroutine.awaitAny"); + int i = 0; + for (Command command : commands) { + requireNonNullParam(command, "commands[" + i + "]", "Coroutine.awaitAny"); + i++; + } + validateNoConflicts(commands); // Schedule anything that's not already queued or running @@ -245,20 +312,6 @@ private static void validateNoConflicts(Collection commands) { * Waits for some duration of time to elapse. Returns immediately if the given duration is zero or * negative. Call this within a command or command composition to introduce a simple delay. * - *

    Note that the resolution of the wait period is equal to the period at which {@link - * Scheduler#run()} is called by the robot program. If using a 20 millisecond update period, the - * wait will be rounded up to the nearest 20 millisecond interval; in this scenario, calling - * {@code wait(Milliseconds.of(1))} and {@code wait(Milliseconds.of(19))} would have identical - * effects. - * - *

    Very small loop times near the loop period are sensitive to the order in which commands are - * executed. If a command waits for 10 ms at the end of a scheduler cycle, and then all the - * commands that ran before it complete or exit, and then the next cycle starts immediately, the - * wait will be evaluated at the start of that next cycle, which occurred less than 10 ms - * later. Therefore the wait will see not enough time has passed and only exit after an additional - * cycle elapses, adding an unexpected extra 20 ms to the wait time. Note that this becomes less - * of a problem with smaller loop periods, as the extra 1-loop delay becomes smaller. - * *

    For example, a basic autonomous routine that drives straight for 5 seconds: * *

    {@code
    @@ -271,12 +324,28 @@ private static void validateNoConflicts(Collection commands) {
        * }
        * }
    * + *

    Note that the resolution of the wait period is equal to the period at which {@link + * Scheduler#run()} is called by the robot program. If using a 20 millisecond update period, the + * wait will be rounded up to the nearest 20 millisecond interval; in this scenario, calling + * {@code wait(Milliseconds.of(1))} and {@code wait(Milliseconds.of(19))} would have identical + * effects. + * + *

    Very small loop times near the loop period are sensitive to the order in which commands are + * executed. If a command waits for 10 ms at the end of a scheduler cycle, and then all the + * commands that ran before it complete or exit, and then the next cycle starts immediately, the + * wait will be evaluated at the start of that next cycle, which occurred less than 10 ms + * later. Therefore, the wait will see not enough time has passed and only exit after an + * additional cycle elapses, adding an unexpected extra 20 ms to the wait time. This becomes less + * of a problem with smaller loop periods, as the extra 1-loop delay becomes smaller. + * * @param duration the duration of time to wait * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void wait(Time duration) { requireMounted(); + requireNonNullParam(duration, "duration", "Coroutine.wait"); + await(new WaitCommand(duration)); } @@ -289,6 +358,8 @@ public void wait(Time duration) { public void waitUntil(BooleanSupplier condition) { requireMounted(); + requireNonNullParam(condition, "condition", "Coroutine.waitUntil"); + while (!condition.getAsBoolean()) { this.yield(); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 36b7af97d34..e5c3dc7af6a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -6,6 +6,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; +import java.util.ArrayList; import java.util.Collection; import java.util.HashSet; import java.util.LinkedHashSet; @@ -18,8 +19,8 @@ * has reached its completion condition will be cancelled. */ public class ParallelGroup implements Command { - private final Collection m_commands = new LinkedHashSet<>(); private final Collection m_requiredCommands = new HashSet<>(); + private final Collection m_optionalCommands = new LinkedHashSet<>(); private final Set m_requirements = new HashSet<>(); private final String m_name; private final int m_priority; @@ -28,30 +29,34 @@ public class ParallelGroup implements Command { * Creates a new parallel group. * * @param name The name of the group. - * @param allCommands All the commands to run in parallel. - * @param requiredCommands The commands that are required to completed for the group to finish. If - * this is empty, then the group will finish when any command in it has completed. + * @param requiredCommands The commands that are required to complete for the group to finish. If + * this is empty, then the group will finish when any optional command completes. + * @param optionalCommands The commands that do not need to complete for the group to finish. If + * this is empty, then the group will finish when all required commands complete. */ @SuppressWarnings("PMD.CompareObjectsWithEquals") public ParallelGroup( - String name, Collection allCommands, Collection requiredCommands) { + String name, Collection requiredCommands, Collection optionalCommands) { requireNonNullParam(name, "name", "ParallelGroup"); - requireNonNullParam(allCommands, "allCommands", "ParallelGroup"); requireNonNullParam(requiredCommands, "requiredCommands", "ParallelGroup"); + requireNonNullParam(optionalCommands, "optionalCommands", "ParallelGroup"); - allCommands.forEach( - c -> { - requireNonNullParam(c, "allCommands[x]", "ParallelGroup"); - }); - requiredCommands.forEach( - c -> { - requireNonNullParam(c, "requiredCommands[x]", "ParallelGroup"); - }); - - if (!allCommands.containsAll(requiredCommands)) { - throw new IllegalArgumentException("Required commands must also be composed"); + int i = 0; + for (Command requiredCommand : requiredCommands) { + requireNonNullParam(requiredCommand, "requiredCommands[" + i + "]", "ParallelGroup"); + i++; } + i = 0; + for (Command c : optionalCommands) { + requireNonNullParam(c, "optionalCommands[" + i + "]", "ParallelGroup"); + i++; + } + + var allCommands = new ArrayList(); + allCommands.addAll(requiredCommands); + allCommands.addAll(optionalCommands); + for (Command c1 : allCommands) { for (Command c2 : allCommands) { if (c1 == c2) { @@ -70,7 +75,7 @@ public ParallelGroup( } m_name = name; - m_commands.addAll(allCommands); + m_optionalCommands.addAll(optionalCommands); m_requiredCommands.addAll(requiredCommands); for (var command : allCommands) { @@ -104,17 +109,17 @@ public static ParallelGroupBuilder all(Command... commands) { @Override public void run(Coroutine coroutine) { + coroutine.forkAll(m_optionalCommands); + if (m_requiredCommands.isEmpty()) { - // No command is explicitly required to complete - // Schedule everything and wait for the first one to complete - coroutine.awaitAny(m_commands); + // No required commands - just wait for the first optional command to finish + coroutine.awaitAny(m_optionalCommands); } else { - // At least one command is required to complete - // Schedule all the non-required commands (the scheduler will automatically cancel them - // when this group completes), and await completion of all the required commands - m_commands.forEach(coroutine.scheduler()::schedule); + // Wait for every required command to finish coroutine.awaitAll(m_requiredCommands); } + + // The scheduler will cancel any optional child commands that are still running when } @Override diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 0e8f4a2be8e..ae9b9722e97 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -4,6 +4,8 @@ package org.wpilib.commands3; +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + import java.util.Arrays; import java.util.LinkedHashSet; import java.util.Set; @@ -35,6 +37,11 @@ public ParallelGroupBuilder() {} * @return The builder object, for chaining */ public ParallelGroupBuilder optional(Command... commands) { + requireNonNullParam(commands, "commands", "ParallelGroupBuilder.optional"); + for (int i = 0; i < commands.length; i++) { + requireNonNullParam(commands[i], "commands[" + i + "]", "ParallelGroupBuilder.optional"); + } + m_commands.addAll(Arrays.asList(commands)); return this; } @@ -47,6 +54,11 @@ public ParallelGroupBuilder optional(Command... commands) { * @return The builder object, for chaining */ public ParallelGroupBuilder requiring(Command... commands) { + requireNonNullParam(commands, "commands", "ParallelGroupBuilder.requiring"); + for (int i = 0; i < commands.length; i++) { + requireNonNullParam(commands[i], "commands[" + i + "]", "ParallelGroupBuilder.requiring"); + } + m_requiredCommands.addAll(Arrays.asList(commands)); m_commands.addAll(m_requiredCommands); return this; @@ -93,7 +105,7 @@ public ParallelGroupBuilder requireAll() { * {@code .until(() -> conditionA()).until(() -> conditionB())}), then the last end condition * added will be used and any previously configured condition will be overridden. * - * @param condition The end condition for the group + * @param condition The end condition for the group. May be null. * @return The builder object, for chaining */ public ParallelGroupBuilder until(BooleanSupplier condition) { @@ -110,6 +122,8 @@ public ParallelGroupBuilder until(BooleanSupplier condition) { * @return The built group */ public ParallelGroup named(String name) { + requireNonNullParam(name, "name", "ParallelGroupBuilder.named"); + var group = new ParallelGroup(name, m_commands, m_requiredCommands); if (m_endCondition == null) { // No custom end condition, return the group as is diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 7e0e406671e..aedf8108e52 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -20,6 +20,8 @@ import java.util.LinkedHashSet; import java.util.List; import java.util.Map; +import java.util.SequencedMap; +import java.util.SequencedSet; import java.util.Set; import java.util.Stack; import java.util.function.Consumer; @@ -95,17 +97,20 @@ public class Scheduler implements ProtobufSerializable { private final Map m_defaultCommands = new LinkedHashMap<>(); /** The set of commands scheduled since the start of the previous run. */ - private final Set m_onDeck = new LinkedHashSet<>(); + private final SequencedSet m_queuedToRun = new LinkedHashSet<>(); - /** The states of all running commands (does not include on deck commands). */ - private final Map m_commandStates = new LinkedHashMap<>(); + /** + * The states of all running commands (does not include on deck commands). We preserve insertion + * order to guarantee that child commands run after their parents. + */ + private final SequencedMap m_runningCommands = new LinkedHashMap<>(); /** * The stack of currently executing commands. Child commands are pushed onto the stack and popped * when they complete. Use {@link #currentState()} and {@link #currentCommand()} to get the * currently executing command or its state. */ - private final Stack m_executingCommands = new Stack<>(); + private final Stack m_currentCommandAncestry = new Stack<>(); /** The periodic callbacks to run, outside of the command structure. */ private final List m_periodicCallbacks = new ArrayList<>(); @@ -238,27 +243,24 @@ public enum ScheduleResult { } /** - * Schedules a command to run. If a running command schedules another command (for example, - * parallel groups will do this), then the new command is assumed to be a bound child of the - * running command. Child commands will automatically be cancelled by the scheduler when their - * parent command completes or is canceled. Child commands will also immediately begin execution, - * without needing to wait for the next {@link #run()} invocation. This allows highly nested - * compositions to begin running the actual meaningful commands sooner without needing to wait one - * scheduler cycle per nesting level; with the default 20ms update period, 5 levels of nesting - * would be enough to delay actions by 100 milliseconds - instead of only 20. + * Schedules a command to run. If one command schedules another (a "parent" and "child"), the + * child command will be canceled when the parent command completes. It is not possible to fork a + * child command and have it live longer than its parent. * *

    Does nothing if the command is already scheduled or running, or requires at least one * mechanism already used by a higher priority command. * - *

    If one command schedules another ("parent" and "fork"), the forked command will be canceled - * when the parent command completes. It is not possible to fork a command and have it live longer - * than the command that forked it. - * * @param command the command to schedule * @return the result of the scheduling attempt. See {@link ScheduleResult} for details. * @throws IllegalArgumentException if scheduled by a command composition that has already * scheduled another command that shares at least one required mechanism */ + // Implementation detail: a child command will immediately start running when scheduled by a + // parent command, skipping the queue entirely. This avoids dead loop cycles where a parent + // schedules a child, appending it to the queue, then waits for the next cycle to pick it up and + // start it. With deeply nested commands, dead loops could quickly to add up and cause the + // innermost commands that actually _do_ something to start running hundreds of milliseconds after + // their root ancestor was scheduled. public ScheduleResult schedule(Command command) { // Note: we use a throwable here instead of Thread.currentThread().getStackTrace() for easier // stack frame filtering and modification. @@ -277,11 +279,11 @@ ScheduleResult schedule(Binding binding) { return ScheduleResult.ALREADY_RUNNING; } - if (!isSchedulable(command)) { + if (lowerPriorityThanConflictingCommands(command)) { return ScheduleResult.LOWER_PRIORITY_THAN_RUNNING_COMMAND; } - for (var scheduledState : m_onDeck) { + for (var scheduledState : m_queuedToRun) { if (!command.conflictsWith(scheduledState.command())) { // No shared requirements, skip continue; @@ -298,52 +300,46 @@ ScheduleResult schedule(Binding binding) { // so at this point we're guaranteed to be >= priority than anything already on deck evictConflictingOnDeckCommands(command); - // If the binding was declared inside a running command, that command is the parent (the current - // command will always be null in this case, since triggers are polled before commands are - // mounted and run). Otherwise, the parent is the command that's running at the time `schedule` - // is called - which may be null. - var parent = + // If the binding is scoped to a particular command, that command is the parent. If we're in the + // middle of a run cycle and running commands, the parent is whatever command is currently + // running. Otherwise, there is no parent command. + var parentCommand = binding.scope() instanceof BindingScope.ForCommand scope ? scope.command() : currentCommand(); - var state = new CommandState(command, parent, buildCoroutine(command), binding); + var state = new CommandState(command, parentCommand, buildCoroutine(command), binding); - emitEvent(scheduled(command)); + emitScheduledEvent(command); if (currentState() != null) { // Scheduling a child command while running. Start it immediately instead of waiting a full // cycle. This prevents issues with deeply nested command groups taking many scheduler cycles - // to start running the commands that actually /do/ things + // to start running the commands that actually _do_ things evictConflictingRunningCommands(state); - m_commandStates.put(command, state); + m_runningCommands.put(command, state); runCommand(state); } else { // Scheduling outside a command, add it to the pending set. If it's not overridden by another // conflicting command being scheduled in the same scheduler loop, it'll be promoted and // start to run when #runCommands() is called - m_onDeck.add(state); + m_queuedToRun.add(state); } return ScheduleResult.SUCCESS; } /** - * Checks if a command can be scheduled. Requirements are that the command either does not - * conflict with any running commands, or is at least the same priority as every running command - * with which it conflicts. If a parent command is attempting to schedule a child, the child will - * never be considered to be conflicting with the parent or any ancestors. - * - * @param command The command to check - * @return True if the command meets all scheduling requirements, false if not + * Checks if a command conflicts with and is a lower priority than any running command. Used when + * determining if the command can be scheduled. */ - private boolean isSchedulable(Command command) { + private boolean lowerPriorityThanConflictingCommands(Command command) { Set ancestors = new HashSet<>(); - for (var state = currentState(); state != null; state = m_commandStates.get(state.parent())) { + for (var state = currentState(); state != null; state = m_runningCommands.get(state.parent())) { ancestors.add(state); } // Check for conflicts with the commands that are already running - for (var state : m_commandStates.values()) { + for (var state : m_runningCommands.values()) { if (ancestors.contains(state)) { // Can't conflict with an ancestor command continue; @@ -351,15 +347,15 @@ private boolean isSchedulable(Command command) { var c = state.command(); if (c.conflictsWith(command) && command.isLowerPriorityThan(c)) { - return false; + return true; } } - return true; + return false; } private void evictConflictingOnDeckCommands(Command command) { - for (var iterator = m_onDeck.iterator(); iterator.hasNext(); ) { + for (var iterator = m_queuedToRun.iterator(); iterator.hasNext(); ) { var scheduledState = iterator.next(); var scheduledCommand = scheduledState.command(); if (scheduledCommand.conflictsWith(command)) { @@ -367,7 +363,7 @@ private void evictConflictingOnDeckCommands(Command command) { // We don't need to call removeOrphanedChildren here because it hasn't started yet, // meaning it hasn't had a chance to schedule any children iterator.remove(); - emitEvent(interrupted(scheduledCommand, command)); + emitInterruptedEvent(scheduledCommand, command); } } } @@ -380,9 +376,9 @@ private void evictConflictingOnDeckCommands(Command command) { private void evictConflictingRunningCommands(CommandState incomingState) { // The set of root states with which the incoming state conflicts but does not inherit from Set conflictingRootStates = - m_commandStates.values().stream() + m_runningCommands.values().stream() .filter(state -> incomingState.command().conflictsWith(state.command())) - .filter(state -> !inheritsFrom(incomingState, state.command())) + .filter(state -> !isAncestorOf(state.command(), incomingState)) .map( state -> { // Find the highest level ancestor of the conflicting command from which the @@ -391,7 +387,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { // incoming command CommandState root = state; while (root.parent() != null && root.parent() != incomingState.parent()) { - root = m_commandStates.get(root.parent()); + root = m_runningCommands.get(root.parent()); } return root; }) @@ -399,7 +395,7 @@ private void evictConflictingRunningCommands(CommandState incomingState) { // Cancel the root commands for (var conflictingState : conflictingRootStates) { - emitEvent(interrupted(conflictingState.command(), incomingState.command())); + emitInterruptedEvent(conflictingState.command(), incomingState.command()); cancel(conflictingState.command()); } } @@ -407,17 +403,17 @@ private void evictConflictingRunningCommands(CommandState incomingState) { /** * Checks if a particular command is an ancestor of another. * - * @param state the state to check * @param ancestor the potential ancestor for which to search + * @param state the state to check * @return true if {@code ancestor} is the direct parent or indirect ancestor, false if not */ @SuppressWarnings({"PMD.CompareObjectsWithEquals", "PMD.SimplifyBooleanReturns"}) - private boolean inheritsFrom(CommandState state, Command ancestor) { + private boolean isAncestorOf(Command ancestor, CommandState state) { if (state.parent() == null) { // No parent, cannot inherit return false; } - if (!m_commandStates.containsKey(ancestor)) { + if (!m_runningCommands.containsKey(ancestor)) { // The given ancestor isn't running return false; } @@ -426,9 +422,9 @@ private boolean inheritsFrom(CommandState state, Command ancestor) { return true; } // Check if the command's parent inherits from the given ancestor - return m_commandStates.values().stream() + return m_runningCommands.values().stream() .filter(s -> state.parent() == s.command()) - .anyMatch(s -> inheritsFrom(s, ancestor)); + .anyMatch(s -> isAncestorOf(ancestor, s)); } /** @@ -447,14 +443,14 @@ public void cancel(Command command) { // Evict the command. The next call to run() will schedule the default command for all its // required mechanisms, unless another command requiring those mechanisms is scheduled between // calling cancel() and calling run() - m_commandStates.remove(command); - m_onDeck.removeIf(state -> state.command() == command); + m_runningCommands.remove(command); + m_queuedToRun.removeIf(state -> state.command() == command); if (running) { // Only run the hook if the command was running. If it was on deck or not // even in the scheduler at the time, then there's nothing to do command.onCancel(); - emitEvent(evicted(command)); + emitEvictedEvent(command); } // Clean up any orphaned child commands; their lifespan must not exceed the parent's @@ -488,18 +484,18 @@ public void run() { private void promoteScheduledCommands() { // Clear any commands that conflict with the scheduled set - for (var queuedState : m_onDeck) { + for (var queuedState : m_queuedToRun) { evictConflictingRunningCommands(queuedState); } // Move any scheduled commands to the running set - for (var queuedState : m_onDeck) { - m_commandStates.put(queuedState.command(), queuedState); + for (var queuedState : m_queuedToRun) { + m_runningCommands.put(queuedState.command(), queuedState); } // Clear the set of on-deck commands, // since we just put them all into the set of running commands - m_onDeck.clear(); + m_queuedToRun.clear(); } private void runPeriodicSideloads() { @@ -522,7 +518,7 @@ private void runCommands() { // Run in reverse so parent commands can resume in the same loop cycle an awaited child command // completes. Otherwise, parents could only resume on the next loop cycle, introducing a delay // at every layer of nesting. - for (var state : List.copyOf(m_commandStates.values()).reversed()) { + for (var state : List.copyOf(m_runningCommands.values()).reversed()) { runCommand(state); } } @@ -537,16 +533,16 @@ private void runCommand(CommandState state) { final var command = state.command(); final var coroutine = state.coroutine(); - if (!m_commandStates.containsKey(command)) { + if (!m_runningCommands.containsKey(command)) { // Probably canceled by an owning composition, do not run return; } var previousState = currentState(); - m_executingCommands.push(state); + m_currentCommandAncestry.push(state); long startMicros = RobotController.getTime(); - emitEvent(mounted(command)); + emitMountedEvent(command); coroutine.mount(); try { coroutine.runToYieldPoint(); @@ -554,7 +550,7 @@ private void runCommand(CommandState state) { // Intercept the exception, inject stack frames from the schedule site, and rethrow it var binding = state.binding(); e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); - emitEvent(completedWithError(command, e)); + emitCompletedWithErrorEvent(command, e); throw e; } finally { long endMicros = RobotController.getTime(); @@ -563,7 +559,7 @@ private void runCommand(CommandState state) { if (state.equals(currentState())) { // Remove the command we just ran from the top of the stack - m_executingCommands.pop(); + m_currentCommandAncestry.pop(); } if (previousState != null) { @@ -577,12 +573,12 @@ private void runCommand(CommandState state) { if (coroutine.isDone()) { // Immediately check if the command has completed and remove any children commands. // This prevents child commands from being executed one extra time in the run() loop - emitEvent(completed(command)); - m_commandStates.remove(command); + emitCompletedEvent(command); + m_runningCommands.remove(command); removeOrphanedChildren(command); } else { // Yielded - emitEvent(yielded(command)); + emitYieldedEvent(command); } } @@ -592,12 +588,12 @@ private void runCommand(CommandState state) { * @return the currently executing command state */ private CommandState currentState() { - if (m_executingCommands.isEmpty()) { + if (m_currentCommandAncestry.isEmpty()) { // Avoid EmptyStackException return null; } - return m_executingCommands.peek(); + return m_currentCommandAncestry.peek(); } /** @@ -619,8 +615,8 @@ private void scheduleDefaultCommands() { // scheduled command. m_defaultCommands.forEach( (mechanism, defaultCommand) -> { - if (m_commandStates.keySet().stream().noneMatch(c -> c.requires(mechanism)) - && m_onDeck.stream().noneMatch(c -> c.command().requires(mechanism)) + if (m_runningCommands.keySet().stream().noneMatch(c -> c.requires(mechanism)) + && m_queuedToRun.stream().noneMatch(c -> c.command().requires(mechanism)) && defaultCommand != null) { // Nothing currently running or scheduled // Schedule the mechanism's default command, if it has one @@ -637,7 +633,7 @@ private void scheduleDefaultCommands() { */ @SuppressWarnings("PMD.CompareObjectsWithEquals") private void removeOrphanedChildren(Command parent) { - m_commandStates.entrySet().stream() + m_runningCommands.entrySet().stream() .filter(e -> e.getValue().parent() == parent) .toList() // copy to an intermediate list to avoid concurrent modification .forEach(e -> cancel(e.getKey())); @@ -661,7 +657,7 @@ private Coroutine buildCoroutine(Command command) { * @return true if the command is running, false if not */ public boolean isRunning(Command command) { - return m_commandStates.containsKey(command); + return m_runningCommands.containsKey(command); } /** @@ -672,7 +668,7 @@ public boolean isRunning(Command command) { */ @SuppressWarnings("PMD.CompareObjectsWithEquals") public boolean isScheduled(Command command) { - return m_onDeck.stream().anyMatch(state -> state.command() == command); + return m_queuedToRun.stream().anyMatch(state -> state.command() == command); } /** @@ -692,7 +688,7 @@ public boolean isScheduledOrRunning(Command command) { * @return the currently running commands */ public Collection getRunningCommands() { - return Collections.unmodifiableSet(m_commandStates.keySet()); + return Collections.unmodifiableSet(m_runningCommands.keySet()); } /** @@ -703,7 +699,7 @@ public Collection getRunningCommands() { * @return the currently running commands that require the mechanism. */ public List getRunningCommandsFor(Mechanism mechanism) { - return m_commandStates.keySet().stream() + return m_runningCommands.keySet().stream() .filter(command -> command.requires(mechanism)) .toList(); } @@ -714,16 +710,16 @@ public List getRunningCommandsFor(Mechanism mechanism) { * after {@code cancelAll()} is used. */ public void cancelAll() { - for (var onDeckIter = m_onDeck.iterator(); onDeckIter.hasNext(); ) { + for (var onDeckIter = m_queuedToRun.iterator(); onDeckIter.hasNext(); ) { var state = onDeckIter.next(); onDeckIter.remove(); - emitEvent(evicted(state.command())); + emitEvictedEvent(state.command()); } - for (var liveIter = m_commandStates.entrySet().iterator(); liveIter.hasNext(); ) { + for (var liveIter = m_runningCommands.entrySet().iterator(); liveIter.hasNext(); ) { var entry = liveIter.next(); liveIter.remove(); - emitEvent(evicted(entry.getKey())); + emitEvictedEvent(entry.getKey()); } } @@ -745,7 +741,7 @@ public EventLoop getDefaultEventLoop() { * @return The commands that have been scheduled but not yet started. */ public Collection getQueuedCommands() { - return m_onDeck.stream().map(CommandState::command).toList(); + return m_queuedToRun.stream().map(CommandState::command).toList(); } /** @@ -756,7 +752,7 @@ public Collection getQueuedCommands() { * another command. */ public Command getParentOf(Command command) { - var state = m_commandStates.get(command); + var state = m_runningCommands.get(command); if (state == null) { return null; } @@ -771,8 +767,8 @@ public Command getParentOf(Command command) { * @return How long, in milliseconds, the command last took to execute. */ public double lastCommandRuntimeMs(Command command) { - if (m_commandStates.containsKey(command)) { - return m_commandStates.get(command).lastRuntimeMs(); + if (m_runningCommands.containsKey(command)) { + return m_runningCommands.get(command).lastRuntimeMs(); } else { return -1; } @@ -786,8 +782,8 @@ public double lastCommandRuntimeMs(Command command) { * @return How long, in milliseconds, the command has taken to execute in total */ public double totalRuntimeMs(Command command) { - if (m_commandStates.containsKey(command)) { - return m_commandStates.get(command).totalRuntimeMs(); + if (m_runningCommands.containsKey(command)) { + return m_runningCommands.get(command).totalRuntimeMs(); } else { // Not running; no data return -1; @@ -803,12 +799,12 @@ public double totalRuntimeMs(Command command) { */ @SuppressWarnings("PMD.CompareObjectsWithEquals") public int runId(Command command) { - if (m_commandStates.containsKey(command)) { - return m_commandStates.get(command).id(); + if (m_runningCommands.containsKey(command)) { + return m_runningCommands.get(command).id(); } // Check scheduled commands - for (var scheduled : m_onDeck) { + for (var scheduled : m_queuedToRun) { if (scheduled.command() == command) { return scheduled.id(); } @@ -830,32 +826,39 @@ public double lastRuntimeMs() { // Event-base telemetry and helpers. The static factories are for convenience to automatically // set the timestamp instead of littering RobotController.getTime() everywhere. - private static SchedulerEvent scheduled(Command command) { - return new SchedulerEvent.Scheduled(command, RobotController.getTime()); + private void emitScheduledEvent(Command command) { + var event = new SchedulerEvent.Scheduled(command, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent mounted(Command command) { - return new SchedulerEvent.Mounted(command, RobotController.getTime()); + private void emitMountedEvent(Command command) { + var event = new SchedulerEvent.Mounted(command, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent yielded(Command command) { - return new SchedulerEvent.Yielded(command, RobotController.getTime()); + private void emitYieldedEvent(Command command) { + var event = new SchedulerEvent.Yielded(command, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent completed(Command command) { - return new SchedulerEvent.Completed(command, RobotController.getTime()); + private void emitCompletedEvent(Command command) { + var event = new SchedulerEvent.Completed(command, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent completedWithError(Command command, Throwable error) { - return new SchedulerEvent.CompletedWithError(command, error, RobotController.getTime()); + private void emitCompletedWithErrorEvent(Command command, Throwable error) { + var event = new SchedulerEvent.CompletedWithError(command, error, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent evicted(Command command) { - return new SchedulerEvent.Evicted(command, RobotController.getTime()); + private void emitEvictedEvent(Command command) { + var event = new SchedulerEvent.Evicted(command, RobotController.getTime()); + emitEvent(event); } - private static SchedulerEvent interrupted(Command command, Command interrupter) { - return new SchedulerEvent.Interrupted(command, interrupter, RobotController.getTime()); + private void emitInterruptedEvent(Command command, Command interrupter) { + var event = new SchedulerEvent.Interrupted(command, interrupter, RobotController.getTime()); + emitEvent(event); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index 3f5d7b97b0e..ef7d2c94df7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -4,6 +4,8 @@ package org.wpilib.commands3; +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + import java.util.ArrayList; import java.util.HashSet; import java.util.List; @@ -32,6 +34,12 @@ public class Sequence implements Command { * @param commands the commands to execute within the sequence */ public Sequence(String name, List commands) { + requireNonNullParam(name, "name", "Sequence"); + requireNonNullParam(commands, "commands", "Sequence"); + for (int i = 0; i < commands.size(); i++) { + requireNonNullParam(commands.get(i), "commands[" + i + "]", "Sequence"); + } + m_name = name; m_commands.addAll(commands); @@ -82,11 +90,7 @@ public static SequenceBuilder builder() { * @return A builder for further configuration */ public static SequenceBuilder sequence(Command... commands) { - var builder = new SequenceBuilder(); - for (var command : commands) { - builder.andThen(command); - } - return builder; + return new SequenceBuilder().andThen(commands); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index 26815eb71b5..e520957d701 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -7,6 +7,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import java.util.ArrayList; +import java.util.Arrays; import java.util.List; import java.util.function.BooleanSupplier; import java.util.stream.Collectors; @@ -34,12 +35,29 @@ public SequenceBuilder() {} * @return The builder object, for chaining */ public SequenceBuilder andThen(Command next) { - requireNonNullParam(next, "next", "Sequence.Builder.andThen"); + requireNonNullParam(next, "next", "SequenceBuilder.andThen"); m_steps.add(next); return this; } + /** + * Adds commands to the sequence. Commands will be added to the sequence in the order they are + * passed to this method. + * + * @param nextCommands The next commands in the sequence + * @return The builder object, for chaining + */ + public SequenceBuilder andThen(Command... nextCommands) { + requireNonNullParam(nextCommands, "nextCommands", "SequenceBuilder.andThen"); + for (int i = 0; i < nextCommands.length; i++) { + requireNonNullParam(nextCommands[i], "nextCommands[" + i + "]", "SequenceBuilder.andThen"); + } + + m_steps.addAll(Arrays.asList(nextCommands)); + return this; + } + /** * Adds an end condition to the command group. If this condition is met before all required * commands have completed, the group will exit early. If multiple end conditions are added (e.g. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 89ba7720961..f1472a10e33 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -242,7 +242,7 @@ private void poll() { // and those scopes may become inactive. clearStaleBindings(); - var signal = signal(); + var signal = readSignal(); if (signal == m_previousSignal) { // No change in the signal. Nothing to do @@ -268,7 +268,7 @@ private void poll() { m_previousSignal = signal; } - private Signal signal() { + private Signal readSignal() { if (m_condition.getAsBoolean()) { return Signal.HIGH; } else { @@ -283,9 +283,11 @@ private void clearStaleBindings() { for (var iterator = bindings.iterator(); iterator.hasNext(); ) { var binding = iterator.next(); if (binding.scope().active()) { + // This binding's scope is still active, leave it running continue; } + // The scope is no long active. Remove the binding and immediately cancel its command. iterator.remove(); m_scheduler.cancel(binding.command()); } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index ff3463370d0..01f18b774b7 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -9,6 +9,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import java.util.List; +import java.util.Set; import java.util.concurrent.atomic.AtomicInteger; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -114,7 +115,7 @@ void race() { }) .named("C2"); - var race = new ParallelGroup("Race", List.of(c1, c2), List.of()); + var race = new ParallelGroup("Race", List.of(), List.of(c1, c2)); m_scheduler.schedule(race); // First call to run() should schedule the commands @@ -157,7 +158,7 @@ void nested() { }) .named("Command"); - var inner = ParallelGroup.all(command).named("Inner"); + var inner = new ParallelGroup("Inner", Set.of(command), Set.of()); var outer = ParallelGroup.all(inner).named("Outer"); // Scheduling: Outer group should be on deck From ff4f02fa7c3bd189707040931c1be4e1034e4081 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 30 Aug 2025 22:32:04 -0400 Subject: [PATCH 107/153] Add test for Scheduler.addPeriodic; move yield to end of loop --- .../main/java/org/wpilib/commands3/Scheduler.java | 3 ++- .../java/org/wpilib/commands3/SchedulerTest.java | 13 +++++++++++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index aedf8108e52..471f5777092 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -226,8 +226,9 @@ public void addPeriodic(Runnable callback) { // TODO: Add a unit test for this sideload( coroutine -> { - while (coroutine.yield()) { + while (true) { callback.run(); + coroutine.yield(); } }); } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 43497f1e6cb..c21263bbac2 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -646,6 +646,19 @@ void sideloadThrowingException() { "Bang!", assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); } + @Test + void periodicSideload() { + AtomicInteger count = new AtomicInteger(0); + m_scheduler.addPeriodic(count::incrementAndGet); + assertEquals(0, count.get()); + + m_scheduler.run(); + assertEquals(1, count.get()); + + m_scheduler.run(); + assertEquals(2, count.get()); + } + @Test void nestedMechanisms() { var superstructure = From 48140a268fa7ce362ccf7ce62fd5e3477f911373 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 08:57:12 -0400 Subject: [PATCH 108/153] Remove IdleCommand and WaitCommand in favor of factories --- .../java/org/wpilib/commands3/Command.java | 15 ++++- .../java/org/wpilib/commands3/Coroutine.java | 8 ++- .../org/wpilib/commands3/IdleCommand.java | 64 ------------------- .../java/org/wpilib/commands3/Mechanism.java | 4 +- .../org/wpilib/commands3/WaitCommand.java | 47 -------------- .../org/wpilib/commands3/SchedulerTest.java | 5 +- 6 files changed, 25 insertions(+), 118 deletions(-) delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java delete mode 100644 commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index a57d3f33ee0..33ad69134db 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -209,7 +209,7 @@ default boolean conflictsWith(Command other) { default Command withTimeout(Time timeout) { requireNonNullParam(timeout, "timeout", "Command.withTimeout"); - return race(this, new WaitCommand(timeout)) + return race(this, waitFor(timeout).named("Timeout: " + timeout.toLongString())) .named(name() + " [" + timeout.toLongString() + " timeout]"); } @@ -320,6 +320,19 @@ static NeedsNameBuilderStage waitUntil(BooleanSupplier condition) { return noRequirements().executing(coroutine -> coroutine.waitUntil(condition)); } + /** + * Creates a command that simply waits for a given duration. The command will not require any + * mechanisms. + * + * @param duration How long to wait + * @return A command builder + */ + static NeedsNameBuilderStage waitFor(Time duration) { + requireNonNullParam(duration, "duration", "Command.waitFor"); + + return noRequirements().executing(coroutine -> coroutine.wait(duration)); + } + /** * Creates a command that runs this one and ends when the end condition is met (if this command * has not already exited by then). diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 6651985986f..245a22d2deb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -4,9 +4,11 @@ package org.wpilib.commands3; +import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.units.measure.Time; +import edu.wpi.first.wpilibj.Timer; import java.util.Arrays; import java.util.Collection; import java.util.List; @@ -346,7 +348,11 @@ public void wait(Time duration) { requireNonNullParam(duration, "duration", "Coroutine.wait"); - await(new WaitCommand(duration)); + var timer = new Timer(); + timer.start(); + while (!timer.hasElapsed(duration.in(Seconds))) { + this.yield(); + } } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java deleted file mode 100644 index a16505af9f6..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/IdleCommand.java +++ /dev/null @@ -1,64 +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 org.wpilib.commands3; - -import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; - -import java.util.Objects; -import java.util.Set; - -/** - * An idle command that owns a mechanism without doing anything. It has the lowest possible - * priority, and can be interrupted by any other command that requires the same mechanism. - * Cancellation and interruption function like a normal command. - */ -public final class IdleCommand implements Command { - private final Mechanism m_mechanism; - - /** - * Creates a new idle command. - * - * @param mechanism the mechanism to idle. - */ - public IdleCommand(Mechanism mechanism) { - m_mechanism = requireNonNullParam(mechanism, "mechanism", "IdleCommand"); - } - - @Override - public void run(Coroutine coroutine) { - coroutine.park(); - } - - @Override - public Set requirements() { - return Set.of(m_mechanism); - } - - @Override - public String name() { - return m_mechanism.getName() + "[IDLE]"; - } - - @Override - public int priority() { - // lowest priority - an idle command can be interrupted by anything else - return LOWEST_PRIORITY; - } - - @Override - public String toString() { - return name(); - } - - @Override - public boolean equals(Object obj) { - return obj instanceof IdleCommand other && Objects.equals(m_mechanism, other.m_mechanism); - } - - @Override - public int hashCode() { - return Objects.hash(m_mechanism); - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index 46117b13e31..1d6f925cc29 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -130,7 +130,7 @@ public NeedsNameBuilderStage runRepeatedly(Runnable loopBody) { * @return A new idle command. */ public Command idle() { - return new IdleCommand(this); + return run(Coroutine::park).withPriority(Command.LOWEST_PRIORITY).named(getName() + "[IDLE]"); } /** @@ -139,7 +139,7 @@ public Command idle() { * @param duration How long the mechanism should idle for. * @return A new idle command. */ - public Command idle(Time duration) { + public Command idleFor(Time duration) { return idle().withTimeout(duration); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java b/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java deleted file mode 100644 index a51641f89fb..00000000000 --- a/commandsv3/src/main/java/org/wpilib/commands3/WaitCommand.java +++ /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. - -package org.wpilib.commands3; - -import static edu.wpi.first.units.Units.Seconds; -import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; - -import edu.wpi.first.units.measure.Time; -import edu.wpi.first.wpilibj.Timer; -import java.util.Set; - -/** A command with no requirements that merely waits for a specified duration of time to elapse. */ -public class WaitCommand implements Command { - private final Time m_duration; - - /** - * Creates a new WaitCommand. The command will wait for the given duration of time before - * completing. - * - * @param duration How long to wait for. - */ - public WaitCommand(Time duration) { - m_duration = requireNonNullParam(duration, "duration", "WaitCommand"); - } - - @Override - public void run(Coroutine coroutine) { - var timer = new Timer(); - timer.start(); - while (!timer.hasElapsed(m_duration.in(Seconds))) { - coroutine.yield(); - } - } - - @Override - public String name() { - // Normalize to seconds so all wait commands have the same name format - return "Wait " + m_duration.in(Seconds) + " Seconds"; - } - - @Override - public Set requirements() { - return Set.of(); - } -} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index c21263bbac2..0f67a2a54a7 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -9,7 +9,6 @@ import static edu.wpi.first.units.Units.Seconds; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; -import static org.junit.jupiter.api.Assertions.assertInstanceOf; import static org.junit.jupiter.api.Assertions.assertThrowsExactly; import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; @@ -409,8 +408,8 @@ void cancelAllStartsDefaults() { 1, runningCommands.size(), "mechanism " + mechanism + " should have exactly one running command"); - assertInstanceOf( - IdleCommand.class, + assertEquals( + mechanism.getDefaultCommand(), runningCommands.getFirst(), "mechanism " + mechanism + " is not running the default command"); } From ca4044ef9f59347e821e494aaa1cb93d6fa0393b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:02:08 -0400 Subject: [PATCH 109/153] Document coroutine fork/await as nonblocking and blocking operations --- .../java/org/wpilib/commands3/Coroutine.java | 24 ++++++++++++------- 1 file changed, 16 insertions(+), 8 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 245a22d2deb..8e5a300304c 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -86,18 +86,23 @@ public void park() { } /** - * Forks off a command. It will run until its natural completion, the parent command exits, or the - * parent command cancels it. The parent command will continue executing while the forked command - * runs, and can resync with the forked command using {@link #await(Command)}. + * Schedules a child command and then immediately returns. The child command will run until its + * natural completion, the parent command exits, or the parent command cancels it. + * + *

    This is a nonblocking operation. To fork and then wait for the child command to complete, + * use {@link #await(Command)}. + * + *

    The parent command will continue executing while the child command runs, and can resync with + * the child command using {@link #await(Command)}. * *

    {@code
        * Command example() {
        *   return Command.noRequirements().executing(coroutine -> {
    -   *     Command inner = ...;
    -   *     coroutine.fork(inner);
    +   *     Command child = ...;
    +   *     coroutine.fork(child);
        *     // ... do more things
    -   *     // then sync back up with the inner command
    -   *     coroutine.await(inner);
    +   *     // then sync back up with the child command
    +   *     coroutine.await(child);
        *   }).named("Example");
        * }
        * }
    @@ -107,6 +112,7 @@ public void park() { * * @param commands The commands to fork. * @throws IllegalStateException if called anywhere other than the coroutine's running command + * @see #await(Command) */ public void fork(Command... commands) { requireMounted(); @@ -172,10 +178,12 @@ public void forkAll(Collection commands) { /** * Awaits completion of a command. If the command is not currently scheduled or running, it will - * be scheduled automatically. + * be scheduled automatically. This is a blocking operation and will not return until the command + * completes or has been interrupted by another command scheduled by the same parent. * * @param command the command to await * @throws IllegalStateException if called anywhere other than the coroutine's running command + * @see #fork(Command...) */ public void await(Command command) { requireMounted(); From bf1828e2705ecbb62178730e6f950ff98380a55e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:04:01 -0400 Subject: [PATCH 110/153] Remove ParallelGroupBuilder methods that modified optionalailty --- .../commands3/ParallelGroupBuilder.java | 23 ------------------- 1 file changed, 23 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index ae9b9722e97..6dab2ef13d4 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -76,29 +76,6 @@ public ParallelGroupBuilder alongWith(Command command) { return requiring(command); } - /** - * Forces the group to be a pure race, where the group will finish after the first command in the - * group completes. All other commands in the group will be canceled. - * - * @return The builder object, for chaining - */ - public ParallelGroupBuilder racing() { - m_requiredCommands.clear(); - return this; - } - - /** - * Forces the group to require all its commands to complete, overriding any configured race or - * deadline behaviors. The group will only exit once every command has completed. - * - * @return The builder object, for chaining - */ - public ParallelGroupBuilder requireAll() { - m_requiredCommands.clear(); - m_requiredCommands.addAll(m_commands); - return this; - } - /** * Adds an end condition to the command group. If this condition is met before all required * commands have completed, the group will exit early. If multiple end conditions are added (e.g. From 67b2376b137bb3b2856f85d449b6597ff7a8233c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:21:14 -0400 Subject: [PATCH 111/153] Documentation and import cleanup in button code --- .../java/org/wpilib/commands3/Trigger.java | 9 ++--- .../commands3/button/CommandGenericHID.java | 34 ++++++++----------- .../wpilib/commands3/button/POVButton.java | 10 +++--- 3 files changed, 24 insertions(+), 29 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index f1472a10e33..39c63b66c3d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -15,12 +15,12 @@ import java.util.List; import java.util.Map; import java.util.function.BooleanSupplier; -import org.wpilib.commands3.button.CommandXboxController; /** * Triggers allow users to specify conditions for when commands should run. Triggers can be set up - * to read from joystick and controller buttons (eg {@link CommandXboxController#x()}) or be - * customized to read sensor values or any other arbitrary true/false condition. + * to read from joystick and controller buttons (eg {@link + * org.wpilib.commands3.button.CommandXboxController#x()}) or be customized to read sensor values or + * any other arbitrary true/false condition. * *

    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. @@ -30,7 +30,8 @@ * *

    Trigger bindings created inside a running command will only be active while that command is * running. This is useful for defining trigger-based behavior only in a certain scope and avoids - * needing to create dozens of global triggers. + * needing to create dozens of global triggers. Any commands scheduled by these triggers will be + * canceled when the enclosing command exits. * *

    {@code
      * Command shootWhileAiming = Command.noRequirements().executing(co -> {
    diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java
    index 1e13b8178db..b3e7a710fc1 100644
    --- a/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java
    +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/CommandGenericHID.java
    @@ -5,7 +5,7 @@
     package org.wpilib.commands3.button;
     
     import edu.wpi.first.math.Pair;
    -import edu.wpi.first.wpilibj.DriverStation;
    +import edu.wpi.first.wpilibj.DriverStation.POVDirection;
     import edu.wpi.first.wpilibj.GenericHID;
     import edu.wpi.first.wpilibj.event.EventLoop;
     import java.util.HashMap;
    @@ -88,29 +88,23 @@ public Trigger button(int button, EventLoop loop) {
        * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID,
        * attached to {@link Scheduler#getDefaultEventLoop() the default command scheduler button loop}.
        *
    -   * 

    The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, - * upper-left is 315). - * - * @param angle POV angle in degrees, or -1 for the center / not pressed. + * @param angle POV angle * @return a Trigger instance based around this angle of a POV on the HID. */ - public Trigger pov(DriverStation.POVDirection angle) { + public Trigger pov(POVDirection angle) { return pov(0, angle, m_scheduler.getDefaultEventLoop()); } /** * Constructs a Trigger instance based around this angle of a POV on the HID. * - *

    The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, - * upper-left is 315). - * * @param pov index of the POV to read (starting at 0). Defaults to 0. - * @param angle POV angle in degrees, or -1 for the center / not pressed. + * @param angle POV angle * @param loop the event loop instance to attach the event to. Defaults to {@link * Scheduler#getDefaultEventLoop() the default command scheduler button loop}. * @return a Trigger instance based around this angle of a POV on the HID. */ - public Trigger pov(int pov, DriverStation.POVDirection angle, EventLoop loop) { + public Trigger pov(int pov, POVDirection angle, EventLoop loop) { var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>()); // angle.value is a 4 bit bitfield return cache.computeIfAbsent( @@ -126,7 +120,7 @@ public Trigger pov(int pov, DriverStation.POVDirection angle, EventLoop loop) { * @return a Trigger instance based around the 0 degree angle of a POV on the HID. */ public Trigger povUp() { - return pov(DriverStation.POVDirection.Up); + return pov(POVDirection.Up); } /** @@ -137,7 +131,7 @@ public Trigger povUp() { * @return a Trigger instance based around the 45 degree angle of a POV on the HID. */ public Trigger povUpRight() { - return pov(DriverStation.POVDirection.UpRight); + return pov(POVDirection.UpRight); } /** @@ -148,7 +142,7 @@ public Trigger povUpRight() { * @return a Trigger instance based around the 90 degree angle of a POV on the HID. */ public Trigger povRight() { - return pov(DriverStation.POVDirection.Right); + return pov(POVDirection.Right); } /** @@ -159,7 +153,7 @@ public Trigger povRight() { * @return a Trigger instance based around the 135 degree angle of a POV on the HID. */ public Trigger povDownRight() { - return pov(DriverStation.POVDirection.DownRight); + return pov(POVDirection.DownRight); } /** @@ -170,7 +164,7 @@ public Trigger povDownRight() { * @return a Trigger instance based around the 180 degree angle of a POV on the HID. */ public Trigger povDown() { - return pov(DriverStation.POVDirection.Down); + return pov(POVDirection.Down); } /** @@ -181,7 +175,7 @@ public Trigger povDown() { * @return a Trigger instance based around the 225 degree angle of a POV on the HID. */ public Trigger povDownLeft() { - return pov(DriverStation.POVDirection.DownLeft); + return pov(POVDirection.DownLeft); } /** @@ -192,7 +186,7 @@ public Trigger povDownLeft() { * @return a Trigger instance based around the 270 degree angle of a POV on the HID. */ public Trigger povLeft() { - return pov(DriverStation.POVDirection.Left); + return pov(POVDirection.Left); } /** @@ -203,7 +197,7 @@ public Trigger povLeft() { * @return a Trigger instance based around the 315 degree angle of a POV on the HID. */ public Trigger povUpLeft() { - return pov(DriverStation.POVDirection.UpLeft); + return pov(POVDirection.UpLeft); } /** @@ -214,7 +208,7 @@ public Trigger povUpLeft() { * @return a Trigger instance based around the center position of a POV on the HID. */ public Trigger povCenter() { - return pov(DriverStation.POVDirection.Center); + return pov(POVDirection.Center); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java index fdb91731ec8..154ddbc3f90 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/button/POVButton.java @@ -6,7 +6,7 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.POVDirection; import edu.wpi.first.wpilibj.GenericHID; import org.wpilib.commands3.Trigger; @@ -16,10 +16,10 @@ public class POVButton extends Trigger { * 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 angle The desired angle * @param povNumber The POV number (see {@link GenericHID#getPOV(int)}) */ - public POVButton(GenericHID joystick, DriverStation.POVDirection angle, int povNumber) { + public POVButton(GenericHID joystick, POVDirection angle, int povNumber) { super(() -> joystick.getPOV(povNumber) == angle); requireNonNullParam(joystick, "joystick", "POVButton"); } @@ -28,9 +28,9 @@ public POVButton(GenericHID joystick, DriverStation.POVDirection angle, int povN * 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) + * @param angle The desired angle */ - public POVButton(GenericHID joystick, DriverStation.POVDirection angle) { + public POVButton(GenericHID joystick, POVDirection angle) { this(joystick, angle, 0); } } From 980ad84333b1a04e17dc9ebcb5546714efc73bce Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:22:59 -0400 Subject: [PATCH 112/153] Explicitly handle one-time loop binding Instead of relying on assumptions about the EventLoop.bind implementation --- commandsv3/src/main/java/org/wpilib/commands3/Trigger.java | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 39c63b66c3d..602ff09915f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -48,6 +48,7 @@ public class Trigger implements BooleanSupplier { private Signal m_previousSignal; private final Map> m_bindings = new EnumMap<>(BindingType.class); private final Runnable m_eventLoopCallback = this::poll; + private boolean m_isBoundToEventLoop; // used for lazily binding to the event loop /** * Represents the state of a signal: high or low. Used instead of a boolean for nullity on the @@ -343,8 +344,10 @@ void addBinding(BindingScope scope, BindingType bindingType, Command command) { .computeIfAbsent(bindingType, _k -> new ArrayList<>()) .add(new Binding(scope, bindingType, command, new Throwable().getStackTrace())); - // Ensure this trigger is bound to the event loop. NOP if already bound - m_loop.bind(m_eventLoopCallback); + if (!m_isBoundToEventLoop) { + m_loop.bind(m_eventLoopCallback); + m_isBoundToEventLoop = true; + } } private void addBinding(BindingType bindingType, Command command) { From 9a087555604892259258e367fe1176d9277d9512 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:27:39 -0400 Subject: [PATCH 113/153] Rename Evicted event to Canceled --- .../main/java/org/wpilib/commands3/Scheduler.java | 11 ++++++----- .../java/org/wpilib/commands3/SchedulerEvent.java | 14 +++++--------- 2 files changed, 11 insertions(+), 14 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 471f5777092..80b723602ce 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -365,6 +365,7 @@ private void evictConflictingOnDeckCommands(Command command) { // meaning it hasn't had a chance to schedule any children iterator.remove(); emitInterruptedEvent(scheduledCommand, command); + emitCanceledEvent(scheduledCommand); } } } @@ -451,7 +452,7 @@ public void cancel(Command command) { // Only run the hook if the command was running. If it was on deck or not // even in the scheduler at the time, then there's nothing to do command.onCancel(); - emitEvictedEvent(command); + emitCanceledEvent(command); } // Clean up any orphaned child commands; their lifespan must not exceed the parent's @@ -714,13 +715,13 @@ public void cancelAll() { for (var onDeckIter = m_queuedToRun.iterator(); onDeckIter.hasNext(); ) { var state = onDeckIter.next(); onDeckIter.remove(); - emitEvictedEvent(state.command()); + emitCanceledEvent(state.command()); } for (var liveIter = m_runningCommands.entrySet().iterator(); liveIter.hasNext(); ) { var entry = liveIter.next(); liveIter.remove(); - emitEvictedEvent(entry.getKey()); + emitCanceledEvent(entry.getKey()); } } @@ -852,8 +853,8 @@ private void emitCompletedWithErrorEvent(Command command, Throwable error) { emitEvent(event); } - private void emitEvictedEvent(Command command) { - var event = new SchedulerEvent.Evicted(command, RobotController.getTime()); + private void emitCanceledEvent(Command command) { + var event = new SchedulerEvent.Canceled(command, RobotController.getTime()); emitEvent(event); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index 603a691b0fb..0b64c7721b8 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -67,20 +67,16 @@ record CompletedWithError(Command command, Throwable error, long timestampMicros implements SchedulerEvent {} /** - * An event marking when a command was evicted from the scheduler. Commands may be evicted when - * they've been scheduled, then another command requiring a shared mechanism is scheduled - * afterward; when cancelled via {@link Scheduler#cancel(Command)} or {@link - * Scheduler#cancelAll()}; or when they're running and interrupted by another command requiring a - * shared mechanism. + * An event marking when a command was canceled. * - * @param command The command that was evicted - * @param timestampMicros When the command was evicted + * @param command The command that was canceled + * @param timestampMicros When the command was canceled */ - record Evicted(Command command, long timestampMicros) implements SchedulerEvent {} + record Canceled(Command command, long timestampMicros) implements SchedulerEvent {} /** * An event marking when a command was interrupted by another. Typically followed by an {@link - * Evicted} event. + * Canceled} event. * * @param command The command that was interrupted * @param interrupter The interrupting command From 5982f571cf0c938f181717701dffb2738dbe38c1 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:30:56 -0400 Subject: [PATCH 114/153] Fix cancelAll() not calling cancellation hooks --- .../java/org/wpilib/commands3/Scheduler.java | 4 ++- .../org/wpilib/commands3/SchedulerTest.java | 30 ++++++++++++++++++- 2 files changed, 32 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 80b723602ce..3b84358d93f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -721,7 +721,9 @@ public void cancelAll() { for (var liveIter = m_runningCommands.entrySet().iterator(); liveIter.hasNext(); ) { var entry = liveIter.next(); liveIter.remove(); - emitCanceledEvent(entry.getKey()); + Command canceledCommand = entry.getKey(); + canceledCommand.onCancel(); + emitCanceledEvent(canceledCommand); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 0f67a2a54a7..0623876d802 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -350,7 +350,7 @@ void cancelsEvictsOnDeck() { } @Test - void cancelAlEvictsOnDeck() { + void cancelAllEvictsOnDeck() { var command = Command.noRequirements().executing(Coroutine::park).named("Command"); m_scheduler.schedule(command); m_scheduler.cancelAll(); @@ -373,6 +373,34 @@ void cancelAllCancelsAll() { } } + @Test + void cancelAllCallsOnCancelHookForRunningCommands() { + AtomicBoolean ranHook = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing(Coroutine::park) + .whenCanceled(() -> ranHook.set(true)) + .named("Command"); + m_scheduler.schedule(command); + m_scheduler.run(); + m_scheduler.cancelAll(); + assertTrue(ranHook.get(), "onCancel hook was not called"); + } + + @Test + void cancelAllDoesNotCallOnCancelHookForQueuedCommands() { + AtomicBoolean ranHook = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing(Coroutine::park) + .whenCanceled(() -> ranHook.set(true)) + .named("Command"); + m_scheduler.schedule(command); + // no call to run before cancelAll() + m_scheduler.cancelAll(); + assertFalse(ranHook.get(), "onCancel hook was not called"); + } + @Test void cancelAllStartsDefaults() { var mechanisms = new ArrayList(10); From 3f92f54b7e8c2623bbaec0383ba9f03e97a51caf Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 09:41:19 -0400 Subject: [PATCH 115/153] Add tests for sideload function interactions with commands --- .../org/wpilib/commands3/SchedulerTest.java | 46 +++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 0623876d802..903dd48f45e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -686,6 +686,52 @@ void periodicSideload() { assertEquals(2, count.get()); } + @Test + void sideloadSchedulingCommand() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + // one-shot sideload forks a command and immediately exits + m_scheduler.sideload(co -> co.fork(command)); + m_scheduler.run(); + assertTrue( + m_scheduler.isRunning(command), "command should have started and outlasted the sideload"); + } + + @Test + void childCommandEscapesViaSideload() { + var child = Command.noRequirements().executing(Coroutine::park).named("Child"); + var parent = + Command.noRequirements() + .executing( + parentCoroutine -> { + m_scheduler.sideload(sidelodCoroutine -> sidelodCoroutine.fork(child)); + }) + .named("Parent"); + + m_scheduler.schedule(parent); + m_scheduler.run(); + assertFalse(m_scheduler.isScheduledOrRunning(parent), "parent should have exited"); + assertFalse( + m_scheduler.isScheduledOrRunning(child), + "the sideload to schedule the child should not have run yet"); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(child), "child should have started running"); + } + + @Test + void sideloadCancelingCommand() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command), "command should have started"); + + m_scheduler.sideload(co -> m_scheduler.cancel(command)); + assertTrue(m_scheduler.isRunning(command), "sideload should not have run yet"); + + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command), "sideload should have canceled the command"); + } + @Test void nestedMechanisms() { var superstructure = From bf0c4cfeeed6a8868a29e8a4e46d53b4895f19b2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 14:47:12 -0400 Subject: [PATCH 116/153] Make "canceled" and "canceling" spelling consistent --- .../java/org/wpilib/commands3/BindingType.java | 8 ++++---- .../main/java/org/wpilib/commands3/Command.java | 2 +- .../main/java/org/wpilib/commands3/Coroutine.java | 4 ++-- .../wpilib/commands3/NeedsNameBuilderStage.java | 2 +- .../java/org/wpilib/commands3/ParallelGroup.java | 2 +- .../main/java/org/wpilib/commands3/Scheduler.java | 4 ++-- .../main/java/org/wpilib/commands3/Trigger.java | 2 +- .../java/org/wpilib/commands3/CoroutineTest.java | 2 +- .../java/org/wpilib/commands3/SchedulerTest.java | 14 +++++++------- .../java/org/wpilib/commands3/TriggerTest.java | 6 +++--- 10 files changed, 23 insertions(+), 23 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java index e3f5b84f1cd..188c39acb8e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/BindingType.java @@ -23,23 +23,23 @@ enum BindingType { SCHEDULE_ON_FALLING_EDGE, /** * Schedules (forks) a command on a rising edge signal. If the command is still running on the - * next rising edge, it will be cancelled then; otherwise, it will be scheduled again. + * next rising edge, it will be canceled then; otherwise, it will be scheduled again. */ TOGGLE_ON_RISING_EDGE, /** * Schedules (forks) a command on a falling edge signal. If the command is still running on the - * next falling edge, it will be cancelled then; otherwise, it will be scheduled again. + * next falling edge, it will be canceled then; otherwise, it will be scheduled again. */ TOGGLE_ON_FALLING_EDGE, /** * Schedules a command on a rising edge signal. If the command is still running on the next - * falling edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which would + * falling edge, it will be canceled then - unlike {@link #SCHEDULE_ON_RISING_EDGE}, which would * allow it to continue to run. */ RUN_WHILE_HIGH, /** * Schedules a command on a falling edge signal. If the command is still running on the next - * rising edge, it will be cancelled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which would + * rising edge, it will be canceled then - unlike {@link #SCHEDULE_ON_FALLING_EDGE}, which would * allow it to continue to run. */ RUN_WHILE_LOW diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 33ad69134db..b545559d9ee 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -123,7 +123,7 @@ public interface Command { /** * An optional lifecycle hook that can be implemented to execute some code whenever this command - * is cancelled before it naturally completes. Commands should be careful to do a single-shot + * is canceled before it naturally completes. Commands should be careful to do a single-shot * cleanup (for example, setting a motor to zero volts) and not do any complex looping logic here. */ default void onCancel() { diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 8e5a300304c..9c780b1c3bd 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -71,7 +71,7 @@ public boolean yield() { /** * Parks the current command. No code in a command declared after calling {@code park()} will be - * executed. A parked command will never complete naturally and must be interrupted or cancelled. + * executed. A parked command will never complete naturally and must be interrupted or canceled. * * @throws IllegalStateException if called anywhere other than the coroutine's running command */ @@ -382,7 +382,7 @@ public void waitUntil(BooleanSupplier condition) { /** * Advanced users only: this permits access to the backing command scheduler to run custom logic * not provided by the standard coroutine methods. Any commands manually scheduled through this - * will be cancelled when the parent command exits - it's not possible to "fork" a command that + * will be canceled when the parent command exits - it's not possible to "fork" a command that * lives longer than the command that scheduled it. * * @return the command scheduler backing this coroutine diff --git a/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java index 998481cdc07..13036bc066d 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java @@ -35,7 +35,7 @@ public interface NeedsNameBuilderStage { /** * Optionally sets an end condition for the command. If the end condition returns {@code true} * before the command body set in {@link NeedsExecutionBuilderStage#executing(Consumer)} would - * exit, the command will be cancelled by the scheduler. + * exit, the command will be canceled by the scheduler. * * @param endCondition An optional end condition for the command. May be null. * @return This builder object, for chaining. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index e5c3dc7af6a..7d57331c691 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -16,7 +16,7 @@ * A type of command that runs multiple other commands in parallel. The group will end after all * required commands have completed; if no command is explicitly required for completion, then the * group will end after any command in the group finishes. Any commands still running when the group - * has reached its completion condition will be cancelled. + * has reached its completion condition will be canceled. */ public class ParallelGroup implements Command { private final Collection m_requiredCommands = new HashSet<>(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 3b84358d93f..0b570b4918f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -50,7 +50,7 @@ *

    Danger

    * *

    The scheduler must be used in a single-threaded program. Commands must be scheduled and - * cancelled by the same thread that runs the scheduler, and cannot be run in a virtual thread. + * canceled by the same thread that runs the scheduler, and cannot be run in a virtual thread. * *

    Using the commands framework in a multithreaded environment can cause crashes in the * Java virtual machine at any time, including on an official field during a match. The @@ -889,7 +889,7 @@ public void addEventListener(Consumer listener) { private void emitEvent(SchedulerEvent event) { // TODO: Prevent listeners from interacting with the scheduler. - // Scheduling or cancelling commands while the scheduler is processing will probably cause + // Scheduling or canceling commands while the scheduler is processing will probably cause // bugs in user code or even a program crash. for (var listener : m_eventListeners) { listener.accept(event); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java index 602ff09915f..d9e273f0298 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Trigger.java @@ -278,7 +278,7 @@ private Signal readSignal() { } } - /** Removes bindings in inactive scopes. Running commands tied to those bindings are cancelled. */ + /** Removes bindings in inactive scopes. Running commands tied to those bindings are canceled. */ private void clearStaleBindings() { m_bindings.forEach( (_bindingType, bindings) -> { diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index bb8001397b6..36d22fb9ffc 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -192,7 +192,7 @@ void awaitAnyCleansUp() { assertTrue(secondRan.get()); assertTrue(ranAfterAwait.get()); - // But only the outer command should still be running; secondInner should have been cancelled + // But only the outer command should still be running; secondInner should have been canceled assertEquals(Set.of(outer), m_scheduler.getRunningCommands()); } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 903dd48f45e..061245c7315 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -416,7 +416,7 @@ void cancelAllStartsDefaults() { // Then running should get it into the set of running commands m_scheduler.run(); - // Cancelling should clear out the set of running commands + // Canceling should clear out the set of running commands m_scheduler.cancelAll(); // Then ticking the scheduler once to fully remove the command and schedule the defaults @@ -591,13 +591,13 @@ void doesNotRunOnCancelWhenInterruptingOnDeck() { } @Test - void doesNotRunOnCancelWhenCancellingOnDeck() { + void doesNotRunOnCancelWhenCancelingOnDeck() { var ran = new AtomicBoolean(false); var mechanism = new Mechanism("The mechanism", m_scheduler); var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); m_scheduler.schedule(cmd); - // cancelling before calling .run() + // canceling before calling .run() m_scheduler.cancel(cmd); m_scheduler.run(); @@ -634,7 +634,7 @@ void doesNotRunOnCancelWhenCompleting() { } @Test - void runsOnCancelWhenCancelling() { + void runsOnCancelWhenCanceling() { var ran = new AtomicBoolean(false); var mechanism = new Mechanism("The mechanism", m_scheduler); @@ -647,7 +647,7 @@ void runsOnCancelWhenCancelling() { } @Test - void runsOnCancelWhenCancellingParent() { + void runsOnCancelWhenCancelingParent() { var ran = new AtomicBoolean(false); var mechanism = new Mechanism("The mechanism", m_scheduler); @@ -1015,8 +1015,8 @@ void commandDeadlock() { // Then sees command2 mount, check for command1, then also yield. // This is like two threads spinwaiting for the other to exit. // - // Externally cancelling command2 allows command1 to continue - // Externally cancelling command1 cancels both + // Externally canceling command2 allows command1 to continue + // Externally canceling command1 cancels both var command1 = Command.noRequirements().executing(co -> co.await(ref2.get())).named("Command 1"); var command2 = diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index df027a22d4e..6364729903a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -71,7 +71,7 @@ void whileTrue() { signal.set(false); m_scheduler.run(); - assertFalse(m_scheduler.isRunning(command), "Command should be cancelled on falling edge"); + assertFalse(m_scheduler.isRunning(command), "Command should be canceled on falling edge"); } @Test @@ -87,7 +87,7 @@ void whileFalse() { signal.set(true); m_scheduler.run(); - assertFalse(m_scheduler.isRunning(command), "Command should be cancelled on rising edge"); + assertFalse(m_scheduler.isRunning(command), "Command should be canceled on rising edge"); } @Test @@ -191,7 +191,7 @@ void scopeGoingInactiveCancelsBoundCommand() { m_scheduler.run(); assertFalse( m_scheduler.isRunning(command), - "Command should have been cancelled when scope became inactive"); + "Command should have been canceled when scope became inactive"); } // The scheduler lifecycle polls triggers at the start of `run()` From 32d68c8889004392e62dbd67a4bb1017e17f343f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 16:56:18 -0400 Subject: [PATCH 117/153] Make Continuation and ContinuationScope package-private Too many opportunities for footguns at the moment May be revisited in the future to open up --- .../src/main/java/org/wpilib/commands3/Continuation.java | 4 ++-- .../src/main/java/org/wpilib/commands3/ContinuationScope.java | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java index 425d05cb1b4..6a0f9aa9071 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Continuation.java @@ -26,7 +26,7 @@ *

    Teams don't need to use continuations directly with the commands framework; all mounting and * unmounting is handled by the command scheduler and a coroutine wrapper. */ -public final class Continuation { +final class Continuation { // The underlying jdk.internal.vm.Continuation object // https://github.com/openjdk/jdk/blob/jdk-21%2B35/src/java.base/share/classes/jdk/internal/vm/Continuation.java private final Object m_continuation; @@ -115,7 +115,7 @@ static final class InternalContinuationError extends Error { * @param target the continuation's body */ @SuppressWarnings({"PMD.AvoidRethrowingException", "PMD.AvoidCatchingGenericException"}) - public Continuation(ContinuationScope scope, Runnable target) { + Continuation(ContinuationScope scope, Runnable target) { try { m_continuation = CONSTRUCTOR.invoke(scope.m_continuationScope, target); m_scope = scope; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java index 5e8d7c2541b..27484d88fc7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ContinuationScope.java @@ -10,7 +10,7 @@ import java.util.Objects; /** A continuation scope. */ -public final class ContinuationScope { +final class ContinuationScope { // The underlying jdk.internal.vm.ContinuationScope object // https://github.com/openjdk/jdk/blob/jdk-21%2B35/src/java.base/share/classes/jdk/internal/vm/ContinuationScope.java final Object m_continuationScope; @@ -38,7 +38,7 @@ public final class ContinuationScope { * * @param name The scope's name */ - public ContinuationScope(String name) { + ContinuationScope(String name) { Objects.requireNonNull(name); try { m_continuationScope = CONSTRUCTOR.invoke(name); From fd1b50ae1284ab88c23cda1061925d2e9f261294 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 19:35:48 -0400 Subject: [PATCH 118/153] Parallel and sequential group cleanup Remove unnecessary factory methods (they're redundant with the factories that already exist in `Command`) Make classes final and constructors private. Users must use builders or factory methods and can't instantiate them directly or subclass from them Add missing `toString` to Sequence to match ParallelGroup --- .../org/wpilib/commands3/ParallelGroup.java | 35 ++---------------- .../commands3/ParallelGroupBuilder.java | 2 +- .../java/org/wpilib/commands3/Sequence.java | 37 +++---------------- .../org/wpilib/commands3/SequenceBuilder.java | 2 +- .../wpilib/commands3/ParallelGroupTest.java | 8 ++-- 5 files changed, 14 insertions(+), 70 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 7d57331c691..54f9fb56f47 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -18,7 +18,7 @@ * group will end after any command in the group finishes. Any commands still running when the group * has reached its completion condition will be canceled. */ -public class ParallelGroup implements Command { +public final class ParallelGroup implements Command { private final Collection m_requiredCommands = new HashSet<>(); private final Collection m_optionalCommands = new LinkedHashSet<>(); private final Set m_requirements = new HashSet<>(); @@ -35,7 +35,7 @@ public class ParallelGroup implements Command { * this is empty, then the group will finish when all required commands complete. */ @SuppressWarnings("PMD.CompareObjectsWithEquals") - public ParallelGroup( + ParallelGroup( String name, Collection requiredCommands, Collection optionalCommands) { requireNonNullParam(name, "name", "ParallelGroup"); requireNonNullParam(requiredCommands, "requiredCommands", "ParallelGroup"); @@ -86,27 +86,6 @@ public ParallelGroup( allCommands.stream().mapToInt(Command::priority).max().orElse(Command.DEFAULT_PRIORITY); } - /** - * Creates a parallel group that runs all the given commands until any of them finish. - * - * @param commands the commands to run in parallel - * @return the group - */ - public static ParallelGroupBuilder race(Command... commands) { - return builder().optional(commands); - } - - /** - * Creates a parallel group that runs all the given commands until they all finish. If a command - * finishes early, its required mechanisms will be idle (uncommanded) until the group completes. - * - * @param commands the commands to run in parallel - * @return the group - */ - public static ParallelGroupBuilder all(Command... commands) { - return builder().requiring(commands); - } - @Override public void run(Coroutine coroutine) { coroutine.forkAll(m_optionalCommands); @@ -120,6 +99,7 @@ public void run(Coroutine coroutine) { } // The scheduler will cancel any optional child commands that are still running when + // the `run` method returns } @Override @@ -141,13 +121,4 @@ public int priority() { public String toString() { return "ParallelGroup[name=" + m_name + "]"; } - - /** - * Creates a new parallel group builder with no commands or configurations applied. - * - * @return A new builder. - */ - public static ParallelGroupBuilder builder() { - return new ParallelGroupBuilder(); - } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 6dab2ef13d4..6092f9eecde 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -108,7 +108,7 @@ public ParallelGroup named(String name) { } // We have a custom end condition, so we need to wrap the group in a race - return ParallelGroup.builder() + return new ParallelGroupBuilder() .optional(group, Command.waitUntil(m_endCondition).named("Until Condition")) .named(name); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java index ef7d2c94df7..99650d97057 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java @@ -21,7 +21,7 @@ * entire duration of the sequence. This means that a mechanism owned by one command in the * sequence, but not by a later one, will be uncommanded while that later command executes. */ -public class Sequence implements Command { +public final class Sequence implements Command { private final String m_name; private final List m_commands = new ArrayList<>(); private final Set m_requirements = new HashSet<>(); @@ -33,7 +33,7 @@ public class Sequence implements Command { * @param name the name of the sequence * @param commands the commands to execute within the sequence */ - public Sequence(String name, List commands) { + Sequence(String name, List commands) { requireNonNullParam(name, "name", "Sequence"); requireNonNullParam(commands, "commands", "Sequence"); for (int i = 0; i < commands.size(); i++) { @@ -73,35 +73,8 @@ public int priority() { return m_priority; } - /** - * Creates a new sequence builder to start building a new sequence of commands. - * - * @return A new builder - */ - public static SequenceBuilder builder() { - return new SequenceBuilder(); - } - - /** - * Starts creating a sequence of the given commands. The commands will execute in the order in - * which they are passed to this function. - * - * @param commands The commands to execute in sequence - * @return A builder for further configuration - */ - public static SequenceBuilder sequence(Command... commands) { - return new SequenceBuilder().andThen(commands); - } - - /** - * Creates a command that executes the given commands in sequence. The returned command will - * require all the mechanisms required by every command in the sequence, and will have a priority - * equal to the highest priority of all the given commands. - * - * @param commands The commands to execute in sequence - * @return The sequence command - */ - public static Command of(Command... commands) { - return sequence(commands).withAutomaticName(); + @Override + public String toString() { + return "Sequence[name=" + m_name + "]"; } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index e520957d701..f4f43a212e7 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -86,7 +86,7 @@ public Command named(String name) { } // We have a custom end condition, so we need to wrap the group in a race - return ParallelGroup.builder() + return new ParallelGroupBuilder() .optional(seq, Command.waitUntil(m_endCondition).named("Until Condition")) .named(name); } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 01f18b774b7..62b3a4ede23 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -159,7 +159,7 @@ void nested() { .named("Command"); var inner = new ParallelGroup("Inner", Set.of(command), Set.of()); - var outer = ParallelGroup.all(inner).named("Outer"); + var outer = new ParallelGroup("Outer", Set.of(), Set.of(inner)); // Scheduling: Outer group should be on deck m_scheduler.schedule(outer); @@ -196,7 +196,7 @@ void automaticNameRace() { var b = Command.noRequirements().executing(coroutine -> {}).named("B"); var c = Command.noRequirements().executing(coroutine -> {}).named("C"); - var group = ParallelGroup.builder().optional(a, b, c).withAutomaticName(); + var group = new ParallelGroupBuilder().optional(a, b, c).withAutomaticName(); assertEquals("(A | B | C)", group.name()); } @@ -206,7 +206,7 @@ void automaticNameAll() { var b = Command.noRequirements().executing(coroutine -> {}).named("B"); var c = Command.noRequirements().executing(coroutine -> {}).named("C"); - var group = ParallelGroup.builder().requiring(a, b, c).withAutomaticName(); + var group = new ParallelGroupBuilder().requiring(a, b, c).withAutomaticName(); assertEquals("(A & B & C)", group.name()); } @@ -216,7 +216,7 @@ void automaticNameDeadline() { var b = Command.noRequirements().executing(coroutine -> {}).named("B"); var c = Command.noRequirements().executing(coroutine -> {}).named("C"); - var group = ParallelGroup.builder().requiring(a).optional(b, c).withAutomaticName(); + var group = new ParallelGroupBuilder().requiring(a).optional(b, c).withAutomaticName(); assertEquals("[(A) * (B | C)]", group.name()); } } From 817e0f1702b90b29d1a039ea3a109c63d1edaaaf Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 19:37:23 -0400 Subject: [PATCH 119/153] Rename `Sequence` to `SequentialGroup` --- .../src/main/java/org/wpilib/commands3/Command.java | 11 ++++++----- .../java/org/wpilib/commands3/SequenceBuilder.java | 4 ++-- .../{Sequence.java => SequentialGroup.java} | 12 ++++++------ .../java/org/wpilib/commands3/SchedulerTest.java | 2 +- .../{SequenceTest.java => SequentialGroupTest.java} | 6 +++--- 5 files changed, 18 insertions(+), 17 deletions(-) rename commandsv3/src/main/java/org/wpilib/commands3/{Sequence.java => SequentialGroup.java} (87%) rename commandsv3/src/test/java/org/wpilib/commands3/{SequenceTest.java => SequentialGroupTest.java} (93%) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index b545559d9ee..55cc414e975 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -48,11 +48,12 @@ *

    The recommended way to create a command is using {@link Mechanism#run(Consumer)} or a related * factory method to create commands that require a single mechanism (for example, a command that * drives an elevator up and down or rotates an arm). Commands may be composed into {@link - * ParallelGroup parallel groups} and {@link Sequence sequences} to build more complex behavior out - * of fundamental building blocks. These built-in compositions will require every mechanism used by - * every command in them, even if those commands aren't always running, and thus can leave certain - * required mechanisms in an uncommanded state: owned, but not used, this can lead to - * mechanisms sagging under gravity or running the previous motor control request they were given. + * ParallelGroup parallel groups} and {@link SequentialGroup sequences} to build more complex + * behavior out of fundamental building blocks. These built-in compositions will require every + * mechanism used by every command in them, even if those commands aren't always running, and thus + * can leave certain required mechanisms in an uncommanded state: owned, but not used, this + * can lead to mechanisms sagging under gravity or running the previous motor control request they + * were given. * *

    Advanced Usage

    * diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java index f4f43a212e7..4d54bf9f65b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java @@ -13,7 +13,7 @@ import java.util.stream.Collectors; /** - * A builder class to configure and then create a {@link Sequence}. Like {@link + * A builder class to configure and then create a {@link SequentialGroup}. Like {@link * StagedCommandBuilder}, the final command is created by calling the terminal {@link * #named(String)} method, or with an automatically generated name using {@link * #withAutomaticName()}. @@ -79,7 +79,7 @@ public SequenceBuilder until(BooleanSupplier endCondition) { * @return The built command */ public Command named(String name) { - var seq = new Sequence(name, m_steps); + var seq = new SequentialGroup(name, m_steps); if (m_endCondition != null) { // No custom end condition, return the group as is return seq; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroup.java similarity index 87% rename from commandsv3/src/main/java/org/wpilib/commands3/Sequence.java rename to commandsv3/src/main/java/org/wpilib/commands3/SequentialGroup.java index 99650d97057..e6458527a1b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Sequence.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroup.java @@ -21,7 +21,7 @@ * entire duration of the sequence. This means that a mechanism owned by one command in the * sequence, but not by a later one, will be uncommanded while that later command executes. */ -public final class Sequence implements Command { +public final class SequentialGroup implements Command { private final String m_name; private final List m_commands = new ArrayList<>(); private final Set m_requirements = new HashSet<>(); @@ -33,11 +33,11 @@ public final class Sequence implements Command { * @param name the name of the sequence * @param commands the commands to execute within the sequence */ - Sequence(String name, List commands) { - requireNonNullParam(name, "name", "Sequence"); - requireNonNullParam(commands, "commands", "Sequence"); + SequentialGroup(String name, List commands) { + requireNonNullParam(name, "name", "SequentialGroup"); + requireNonNullParam(commands, "commands", "SequentialGroup"); for (int i = 0; i < commands.size(); i++) { - requireNonNullParam(commands.get(i), "commands[" + i + "]", "Sequence"); + requireNonNullParam(commands.get(i), "commands[" + i + "]", "SequentialGroup"); } m_name = name; @@ -75,6 +75,6 @@ public int priority() { @Override public String toString() { - return "Sequence[name=" + m_name + "]"; + return "SequentialGroup[name=" + m_name + "]"; } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 061245c7315..bd5ecaa4757 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -653,7 +653,7 @@ void runsOnCancelWhenCancelingParent() { var mechanism = new Mechanism("The mechanism", m_scheduler); var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - var group = new Sequence("Seq", Collections.singletonList(cmd)); + var group = new SequentialGroup("Seq", Collections.singletonList(cmd)); m_scheduler.schedule(group); m_scheduler.run(); m_scheduler.cancel(group); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java similarity index 93% rename from commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java rename to commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java index 01f5e0d180c..b821de833b9 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SequenceTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java @@ -11,7 +11,7 @@ import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -class SequenceTest { +class SequentialGroupTest { private Scheduler m_scheduler; @BeforeEach @@ -23,7 +23,7 @@ void setup() { void single() { var command = Command.noRequirements().executing(Coroutine::yield).named("The Command"); - var sequence = new Sequence("The Sequence", List.of(command)); + var sequence = new SequentialGroup("The Sequence", List.of(command)); m_scheduler.schedule(sequence); // First run - the composed command starts and yields; sequence yields @@ -42,7 +42,7 @@ void twoCommands() { var c1 = Command.noRequirements().executing(Coroutine::yield).named("C1"); var c2 = Command.noRequirements().executing(Coroutine::yield).named("C2"); - var sequence = new Sequence("C1 > C2", List.of(c1, c2)); + var sequence = new SequentialGroup("C1 > C2", List.of(c1, c2)); m_scheduler.schedule(sequence); // First run - c1 is scheduled and starts From 00d8c91a2c34ed37ce95510e64f3d917476c78fe Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Mon, 1 Sep 2025 23:54:30 -0400 Subject: [PATCH 120/153] Move conflict detection to utility class Now detects all conflicts in the input, not just the first encountered --- .../wpilib/commands3/ConflictDetector.java | 120 ++++++++++++++++++ .../java/org/wpilib/commands3/Coroutine.java | 44 +------ .../org/wpilib/commands3/ParallelGroup.java | 21 +-- .../commands3/ConflictDetectorTest.java | 80 ++++++++++++ .../wpilib/commands3/ParallelGroupTest.java | 2 +- .../org/wpilib/commands3/SchedulerTest.java | 20 +-- 6 files changed, 215 insertions(+), 72 deletions(-) create mode 100644 commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java b/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java new file mode 100644 index 00000000000..e73c16252e4 --- /dev/null +++ b/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java @@ -0,0 +1,120 @@ +// 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 org.wpilib.commands3; + +import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; + +import java.util.ArrayList; +import java.util.Collection; +import java.util.LinkedHashSet; +import java.util.List; +import java.util.Set; +import java.util.stream.Collectors; + +/** Utility class for helping with detecting conflicts between commands. */ +public final class ConflictDetector { + private ConflictDetector() { + // This is a utility class! + } + + /** + * A conflict between two commands. + * + * @param a The first conflicting command. + * @param b The second conflicting command. + * @param sharedRequirements The set of mechanisms required by both commands. This set is + * read-only + */ + public record Conflict(Command a, Command b, Set sharedRequirements) { + /** + * Gets a descriptive message for the conflict. The description includes the names of the + * conflicting commands and the names of all mechanisms required by both commands. + * + * @return A description of the conflict. + */ + public String description() { + var shared = + sharedRequirements.stream().map(Mechanism::getName).collect(Collectors.joining(", ")); + return "%s and %s both require %s".formatted(a.name(), b.name(), shared); + } + } + + /** + * Validates that a set of commands have no internal requirement conflicts. An error is thrown if + * a conflict is detected. + * + * @param commands The commands to validate + * @throws IllegalArgumentException If at least one pair of commands is found in the input where + * both commands have at least one required mechanism in common + */ + public static void throwIfConflicts(Collection commands) { + requireNonNullParam(commands, "commands", "ConflictDetector.throwIfConflicts"); + + var conflicts = findAllConflicts(commands); + if (conflicts.isEmpty()) { + // No conflicts, all good + return; + } + + StringBuilder message = + new StringBuilder("Commands running in parallel cannot share requirements: "); + for (int i = 0; i < conflicts.size(); i++) { + Conflict conflict = conflicts.get(i); + message.append(conflict.description()); + if (i < conflicts.size() - 1) { + message.append("; "); + } + } + + throw new IllegalArgumentException(message.toString()); + } + + /** + * Finds all conflicting pairs of commands in the input collection. + * + * @param commands The commands to check. + * @return All detected conflicts. The returned list is empty if no conflicts were found. + */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") + public static List findAllConflicts(Collection commands) { + requireNonNullParam(commands, "commands", "ConflictDetector.findAllConflicts"); + + List conflicts = new ArrayList<>(); + + int i = 0; + for (Command command : commands) { + i++; + int j = 0; + for (Command other : commands) { + j++; + if (j <= i) { + // Skip all elements in 0..i so the inner loop only checks elements from i + 1 onward. + // Ordering of the elements in the pair doesn't matter, and this prevents finding every + // pair twice eg (A, B) and (B, A). + continue; + } + + if (command == other) { + // Commands cannot conflict with themselves, so just in case the input collection happens + // to have duplicate elements we just skip any pairs of a command with itself. + continue; + } + + if (command.conflictsWith(other)) { + conflicts.add(findConflict(command, other)); + } + } + } + + return conflicts; + } + + private static Conflict findConflict(Command a, Command b) { + // using a LinkedHashSet for consistent ordering + Set sharedRequirements = new LinkedHashSet<>(a.requirements()); + sharedRequirements.retainAll(b.requirements()); + return new Conflict(a, b, Set.copyOf(sharedRequirements)); + } +} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 9c780b1c3bd..2dfcb156a67 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -14,7 +14,6 @@ import java.util.List; import java.util.function.BooleanSupplier; import java.util.function.Consumer; -import java.util.stream.Collectors; /** * A coroutine object is injected into command's {@link Command#run(Coroutine)} method to allow @@ -123,7 +122,7 @@ public void fork(Command... commands) { } // Check for user error; there's no reason to fork conflicting commands simultaneously - validateNoConflicts(List.of(commands)); + ConflictDetector.throwIfConflicts(List.of(commands)); // Shorthand; this is handy for user-defined compositions for (var command : commands) { @@ -158,7 +157,7 @@ public void fork(Command... commands) { public void forkAll(Collection commands) { requireMounted(); - validateNoConflicts(commands); + ConflictDetector.throwIfConflicts(commands); requireNonNullParam(commands, "commands", "Coroutine.fork"); int i = 0; @@ -168,7 +167,7 @@ public void forkAll(Collection commands) { } // Check for user error; there's no reason to fork conflicting commands simultaneously - validateNoConflicts(commands); + ConflictDetector.throwIfConflicts(commands); // Shorthand; this is handy for user-defined compositions for (var command : commands) { @@ -217,7 +216,7 @@ public void awaitAll(Collection commands) { i++; } - validateNoConflicts(commands); + ConflictDetector.throwIfConflicts(commands); for (var command : commands) { m_scheduler.schedule(command); @@ -258,7 +257,7 @@ public void awaitAny(Collection commands) { i++; } - validateNoConflicts(commands); + ConflictDetector.throwIfConflicts(commands); // Schedule anything that's not already queued or running for (var command : commands) { @@ -285,39 +284,6 @@ public void awaitAny(Command... commands) { awaitAny(Arrays.asList(commands)); } - /** - * Validates that a set of commands have no internal requirement conflicts. An error is thrown if - * a conflict is detected. - * - * @param commands The commands to validate - * @throws IllegalArgumentException If at least one pair of commands is found in the input where - * both commands have at least one required mechanism in common - */ - @SuppressWarnings("PMD.CompareObjectsWithEquals") - private static void validateNoConflicts(Collection commands) { - for (var c1 : commands) { - for (var c2 : commands) { - if (c1 == c2) { - // Commands can't conflict with themselves - continue; - } - - // TODO: Report all pairs of conflicting commands? Instead of just the first one we find - if (c1.conflictsWith(c2)) { - var conflictNames = - c1.requirements().stream() - .filter(c2::requires) - .map(Mechanism::getName) - .collect(Collectors.joining(", ")); - - throw new IllegalArgumentException( - "Command %s requires mechanisms that are already used by %s. Both require %s" - .formatted(c2.name(), c1.name(), conflictNames)); - } - } - } - } - /** * Waits for some duration of time to elapse. Returns immediately if the given duration is zero or * negative. Call this within a command or command composition to introduce a simple delay. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index 54f9fb56f47..bdb46716212 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -6,7 +6,6 @@ import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import java.util.ArrayList; import java.util.Collection; import java.util.HashSet; import java.util.LinkedHashSet; @@ -34,7 +33,6 @@ public final class ParallelGroup implements Command { * @param optionalCommands The commands that do not need to complete for the group to finish. If * this is empty, then the group will finish when all required commands complete. */ - @SuppressWarnings("PMD.CompareObjectsWithEquals") ParallelGroup( String name, Collection requiredCommands, Collection optionalCommands) { requireNonNullParam(name, "name", "ParallelGroup"); @@ -53,26 +51,11 @@ public final class ParallelGroup implements Command { i++; } - var allCommands = new ArrayList(); + var allCommands = new LinkedHashSet(); allCommands.addAll(requiredCommands); allCommands.addAll(optionalCommands); - for (Command c1 : allCommands) { - for (Command c2 : allCommands) { - if (c1 == c2) { - // Commands can't conflict with themselves - continue; - } - if (c1.conflictsWith(c2)) { - throw new IllegalArgumentException( - "Commands in a parallel composition cannot require the same mechanisms. " - + c1.name() - + " and " - + c2.name() - + " conflict."); - } - } - } + ConflictDetector.throwIfConflicts(allCommands); m_name = name; m_optionalCommands.addAll(optionalCommands); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java new file mode 100644 index 00000000000..070efa98a87 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java @@ -0,0 +1,80 @@ +// 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 org.wpilib.commands3; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertThrows; +import static org.wpilib.commands3.ConflictDetector.findAllConflicts; +import static org.wpilib.commands3.ConflictDetector.throwIfConflicts; + +import edu.wpi.first.wpilibj.RobotController; +import java.util.List; +import java.util.Set; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; +import org.wpilib.commands3.ConflictDetector.Conflict; + +class ConflictDetectorTest { + private Scheduler m_scheduler; + + @BeforeEach + void setup() { + RobotController.setTimeSource(() -> System.nanoTime() / 1000L); + m_scheduler = new Scheduler(); + } + + @Test + void emptyInputHasNoConflicts() { + var conflicts = findAllConflicts(List.of()); + assertEquals(0, conflicts.size()); + } + + @Test + void singleInputHasNoConflicts() { + var mech = new Mechanism("Mech", m_scheduler); + var command = Command.requiring(mech).executing(Coroutine::park).named("Command"); + var conflicts = findAllConflicts(List.of(command)); + assertEquals(0, conflicts.size()); + } + + @Test + void commandDoesNotConflictWithSelf() { + var mech = new Mechanism("Mech", m_scheduler); + var command = Command.requiring(mech).executing(Coroutine::park).named("Command"); + var conflicts = findAllConflicts(List.of(command, command)); + assertEquals(0, conflicts.size()); + } + + @Test + void detectManyConflicts() { + var mech1 = new Mechanism("Mech 1", m_scheduler); + var mech2 = new Mechanism("Mech 2", m_scheduler); + + var command1 = Command.requiring(mech1, mech2).executing(Coroutine::park).named("Command1"); + var command2 = Command.requiring(mech1).executing(Coroutine::park).named("Command2"); + var command3 = Command.requiring(mech2).executing(Coroutine::park).named("Command3"); + var command4 = Command.requiring(mech2, mech1).executing(Coroutine::park).named("Command4"); + var allCommands = List.of(command1, command2, command3, command4); + + var conflicts = findAllConflicts(allCommands); + assertEquals(5, conflicts.size(), "Five conflicting pairs should have been found"); + assertEquals(new Conflict(command1, command2, Set.of(mech1)), conflicts.get(0)); + assertEquals(new Conflict(command1, command3, Set.of(mech2)), conflicts.get(1)); + assertEquals(new Conflict(command1, command4, Set.of(mech1, mech2)), conflicts.get(2)); + assertEquals(new Conflict(command2, command4, Set.of(mech1)), conflicts.get(3)); + assertEquals(new Conflict(command3, command4, Set.of(mech2)), conflicts.get(4)); + + // error messaging + var error = assertThrows(IllegalArgumentException.class, () -> throwIfConflicts(allCommands)); + assertEquals( + "Commands running in parallel cannot share requirements: " + + "Command1 and Command2 both require Mech 1; " + + "Command1 and Command3 both require Mech 2; " + + "Command1 and Command4 both require Mech 1, Mech 2; " + + "Command2 and Command4 both require Mech 1; " + + "Command3 and Command4 both require Mech 2", + error.getMessage()); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 62b3a4ede23..9e1fe9ac8d9 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -49,7 +49,7 @@ void parallelAll() { }) .named("C2"); - var parallel = new ParallelGroup("Parallel", List.of(c1, c2), List.of(c1, c2)); + var parallel = new ParallelGroup("Parallel", List.of(c1, c2), List.of()); m_scheduler.schedule(parallel); // First call to run() should schedule and start the commands diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index bd5ecaa4757..17574c35532 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -9,6 +9,7 @@ import static edu.wpi.first.units.Units.Seconds; 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 static org.junit.jupiter.api.Assertions.assertThrowsExactly; import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; @@ -546,9 +547,8 @@ void compositionsDoNotNeedRequirements() { } @Test - @SuppressWarnings("PMD.AvoidCatchingGenericException") void compositionsCannotAwaitConflictingCommands() { - var mech = new Mechanism("The mechanism", m_scheduler); + var mech = new Mechanism("The Mechanism", m_scheduler); var group = Command.noRequirements() @@ -563,17 +563,11 @@ void compositionsCannotAwaitConflictingCommands() { m_scheduler.schedule(group); // Running should attempt to schedule multiple conflicting commands - try { - m_scheduler.run(); - fail("An exception should have been thrown"); - } catch (IllegalArgumentException iae) { - assertEquals( - "Command Second requires mechanisms that are already used by First. " - + "Both require The mechanism", - iae.getMessage()); - } catch (Exception e) { - fail("Unexpected exception: " + e); - } + var exception = assertThrows(IllegalArgumentException.class, m_scheduler::run); + assertEquals( + "Commands running in parallel cannot share requirements: " + + "First and Second both require The Mechanism", + exception.getMessage()); } @Test From 2609056be2c4b1d34d851dadff5a973869888fef Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 2 Sep 2025 21:41:15 -0400 Subject: [PATCH 121/153] Reorder scheduler `run()` cycle Move sideloads before trigger polling to support sideloads that set state for triggers to read Move default command scheduling immediately before queued command promotion so default commands don't take an extra cycle to kick in Rename `scheduleAsDefaultCommand` to `setDefaultCommand` and remove the now-unnecessary `schedule` call --- .../java/org/wpilib/commands3/Mechanism.java | 2 +- .../java/org/wpilib/commands3/Scheduler.java | 42 ++++++++++++------- .../org/wpilib/commands3/SchedulerTest.java | 13 ++++++ 3 files changed, 41 insertions(+), 16 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index 1d6f925cc29..f7e9831a0aa 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -78,7 +78,7 @@ public String getName() { * @param defaultCommand the new default command */ public void setDefaultCommand(Command defaultCommand) { - m_registeredScheduler.scheduleAsDefaultCommand(this, defaultCommand); + m_registeredScheduler.setDefaultCommand(this, defaultCommand); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 0b570b4918f..474102ceb85 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -66,16 +66,16 @@ *

    The {@link #run()} method runs five steps: * *

      - *
    1. Poll all registered triggers to queue and cancel commands *
    2. Call {@link #sideload(Consumer) periodic sideload functions} + *
    3. Poll all registered triggers to queue and cancel commands + *
    4. Queue default commands for any mechanisms without a running command. The queued commands + * can be superseded by any manual scheduling or commands scheduled by triggers in the next + * run. *
    5. Start all queued commands. This happens after all triggers are checked in case multiple * commands with conflicting requirements are queued in the same update; the last command to * be queued takes precedence over the rest. *
    6. Loop over all running commands, mounting and calling each in turn until they either exit or * call {@link Coroutine#yield()}. Commands run in the order in which they were scheduled. - *
    7. Queue default commands for any mechanisms without a running command. The queued commands - * can be superseded by any manual scheduling or commands scheduled by triggers in the next - * run. *
    * *

    Telemetry

    @@ -162,7 +162,7 @@ public Scheduler() {} * @throws IllegalArgumentException if the command does not meet the requirements for being a * default command */ - public void scheduleAsDefaultCommand(Mechanism mechanism, Command defaultCommand) { + public void setDefaultCommand(Mechanism mechanism, Command defaultCommand) { if (!defaultCommand.requires(mechanism)) { throw new IllegalArgumentException( "A mechanism's default command must require that mechanism"); @@ -174,7 +174,6 @@ public void scheduleAsDefaultCommand(Mechanism mechanism, Command defaultCommand } m_defaultCommands.put(mechanism, defaultCommand); - schedule(defaultCommand); } /** @@ -223,7 +222,6 @@ public void sideload(Consumer callback) { * @param callback the periodic function to run */ public void addPeriodic(Runnable callback) { - // TODO: Add a unit test for this sideload( coroutine -> { while (true) { @@ -460,11 +458,17 @@ public void cancel(Command command) { } /** - * Updates the command scheduler. This will process trigger bindings on anything attached to the - * {@link #getDefaultEventLoop() default event loop}, begin running any commands scheduled since - * the previous call to {@code run()}, process periodic callbacks added with {@link - * #addPeriodic(Runnable)} and {@link #sideload(Consumer)}, update running commands, and schedule - * default commands for any mechanisms that are not owned by a running command. + * Updates the command scheduler. This will run operations in the following order: + * + *
      + *
    1. Run sideloaded functions from {@link #sideload(Consumer)} and {@link + * #addPeriodic(Runnable)} + *
    2. Update trigger bindings to queue and cancel bound commands + *
    3. Queue default commands for mechanisms that do not have a queued or running command + *
    4. Promote queued commands to the running set + *
    5. For every command in the running set, mount and run that command until it calls {@link + * Coroutine#yield()} or exits + *
    * *

    This method is intended to be called in a periodic loop like {@link * TimedRobot#robotPeriodic()} @@ -472,13 +476,21 @@ public void cancel(Command command) { public void run() { final long startMicros = RobotController.getTime(); - // Process triggers first; these tend to queue and cancel commands + // Sideloads may change some state that affects triggers. Run them first. + runPeriodicSideloads(); + + // Poll triggers next to schedule and cancel commands m_eventLoop.poll(); - runPeriodicSideloads(); + // Schedule default commands for any mechanisms that don't have a running command and didn't + // have a new command scheduled by a sideload function or a trigger + scheduleDefaultCommands(); + + // Move all scheduled commands to the running set promoteScheduledCommands(); + + // Run every command in order until they call Coroutine.yield() or exit runCommands(); - scheduleDefaultCommands(); final long endMicros = RobotController.getTime(); m_lastRunTimeMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 17574c35532..b77d576ac3d 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -726,6 +726,19 @@ void sideloadCancelingCommand() { assertFalse(m_scheduler.isRunning(command), "sideload should have canceled the command"); } + @Test + void sideloadAffectsStateForTriggerInSameCycle() { + AtomicBoolean signal = new AtomicBoolean(false); + var trigger = new Trigger(m_scheduler, signal::get); + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + trigger.onTrue(command); + m_scheduler.sideload(co -> signal.set(true)); + + m_scheduler.run(); + assertTrue(signal.get(), "Sideload should have run and set the signal"); + assertTrue(m_scheduler.isRunning(command), "Command should have started"); + } + @Test void nestedMechanisms() { var superstructure = From f08a4a0f0be2f2f506ef88325f5bad91361e10ae Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 2 Sep 2025 21:46:35 -0400 Subject: [PATCH 122/153] Sort conflicting mechanism names alphabetically in ConflictDetector For consistency in messaging --- .../java/org/wpilib/commands3/ConflictDetector.java | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java b/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java index e73c16252e4..5be5953fc74 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ConflictDetector.java @@ -8,7 +8,7 @@ import java.util.ArrayList; import java.util.Collection; -import java.util.LinkedHashSet; +import java.util.HashSet; import java.util.List; import java.util.Set; import java.util.stream.Collectors; @@ -36,7 +36,10 @@ public record Conflict(Command a, Command b, Set sharedRequirements) */ public String description() { var shared = - sharedRequirements.stream().map(Mechanism::getName).collect(Collectors.joining(", ")); + sharedRequirements.stream() + .map(Mechanism::getName) + .sorted() + .collect(Collectors.joining(", ")); return "%s and %s both require %s".formatted(a.name(), b.name(), shared); } } @@ -112,8 +115,7 @@ public static List findAllConflicts(Collection comm } private static Conflict findConflict(Command a, Command b) { - // using a LinkedHashSet for consistent ordering - Set sharedRequirements = new LinkedHashSet<>(a.requirements()); + Set sharedRequirements = new HashSet<>(a.requirements()); sharedRequirements.retainAll(b.requirements()); return new Conflict(a, b, Set.copyOf(sharedRequirements)); } From 6aea6dbc80ec6e9c20c96ff12d68684208af5fe1 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 2 Sep 2025 23:00:09 -0400 Subject: [PATCH 123/153] Update design doc with changes to `run()` method steps ordering --- design-docs/commands-v3.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/design-docs/commands-v3.md b/design-docs/commands-v3.md index c9685364601..10e77699f8e 100644 --- a/design-docs/commands-v3.md +++ b/design-docs/commands-v3.md @@ -354,17 +354,17 @@ caused by loop timings for deeply nested commands. ### Scheduler `run()` Cycle -1. Poll the event loop for triggers (which may queue or cancel commands) -2. Run periodic sideload functions -3. Promote scheduled commands to running +1. Run periodic sideload functions +2. Poll the event loop for triggers (which may queue or cancel commands) +3. Schedule default commands for the next iteration to pick up and start running +4. Promote scheduled commands to running 1. Cancels any running commands that conflict with scheduled ones -4. Iterate over running commands +5. Iterate over running commands 1. Mount 2. Run until yield point is reached or an error is raised 3. Unmount 4. Evict if the command finished 1. Any inner command still running is canceled -5. Schedule default commands for the next iteration to pick up and start running ### Interruption From da468443828cdefa9ba1bb2747e0c2c5125ee5cb Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Wed, 3 Sep 2025 08:58:46 -0400 Subject: [PATCH 124/153] Properly clean up after commands that encounter uncaught exceptions Commands with uncaught exceptions will now be removed from the scheduler and their child commands canceled, just as if the command completed normally. `Completed` events are not emitted, however. --- .../java/org/wpilib/commands3/Scheduler.java | 14 ++++ .../org/wpilib/commands3/SchedulerTest.java | 71 +++++++++++++++++++ 2 files changed, 85 insertions(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 474102ceb85..d5da2ff720f 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -438,6 +438,11 @@ private boolean isAncestorOf(Command ancestor, CommandState state) { */ @SuppressWarnings("PMD.CompareObjectsWithEquals") public void cancel(Command command) { + if (command == currentCommand()) { + throw new IllegalArgumentException( + "Command `" + command.name() + "` is mounted and cannot be canceled"); + } + boolean running = isRunning(command); // Evict the command. The next call to run() will schedule the default command for all its @@ -561,10 +566,19 @@ private void runCommand(CommandState state) { try { coroutine.runToYieldPoint(); } catch (RuntimeException e) { + // Command encountered an uncaught exception. + // Remove it from the running set. + m_runningCommands.remove(command); + // Intercept the exception, inject stack frames from the schedule site, and rethrow it var binding = state.binding(); e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); emitCompletedWithErrorEvent(command, e); + // Clean up child commands after emitting the event so child Canceled events are emitted + // after the parent's CompletedWithError + removeOrphanedChildren(command); + + // Then rethrow the exception throw e; } finally { long endMicros = RobotController.getTime(); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index b77d576ac3d..d522cafb61d 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -251,6 +251,54 @@ void nestedErrorDetection() { } } + @Test + void commandEncounteringErrorCancelsChildren() { + var child = Command.noRequirements().executing(Coroutine::park).named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.fork(child); + throw new RuntimeException("The exception"); + }) + .named("Bad Behavior"); + + m_scheduler.schedule(command); + assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isScheduledOrRunning(command), + "Command should have been removed from the scheduler"); + assertFalse( + m_scheduler.isScheduledOrRunning(child), + "Child should have been removed from the scheduler"); + } + + @Test + void childCommandEncounteringErrorCancelsParent() { + var child = + Command.noRequirements() + .executing( + co -> { + throw new RuntimeException("The exception"); // note: bubbles up to the parent + }) + .named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.await(child); + co.park(); // pretend other things would happen after the child + }) + .named("Parent"); + + m_scheduler.schedule(command); + assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isRunning(command), + "Parent command should have been removed from the scheduler"); + assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); + } + @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void runMechanism() { @@ -350,6 +398,29 @@ void cancelsEvictsOnDeck() { assertFalse(m_scheduler.isScheduledOrRunning(command)); } + @Test + void commandCancelingSelf() { + var ranAfterCancel = new AtomicBoolean(false); + var commandRef = new AtomicReference(null); + var command = + Command.noRequirements() + .executing( + co -> { + co.scheduler().cancel(commandRef.get()); + ranAfterCancel.set(true); + }) + .named("Command"); + commandRef.set(command); + m_scheduler.schedule(command); + + var error = assertThrows(IllegalArgumentException.class, () -> m_scheduler.run()); + assertEquals("Command `Command` is mounted and cannot be canceled", error.getMessage()); + assertFalse(ranAfterCancel.get(), "Command should have stopped after encountering an error"); + assertFalse( + m_scheduler.isScheduledOrRunning(command), + "Command should have been removed from the scheduler"); + } + @Test void cancelAllEvictsOnDeck() { var command = Command.noRequirements().executing(Coroutine::park).named("Command"); From 786ce08c1dd2c5f322b6b4dbb556583178b03730 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 4 Sep 2025 08:48:08 -0400 Subject: [PATCH 125/153] Cancel parent commands when child command encounters an error --- .../java/org/wpilib/commands3/Scheduler.java | 58 +++++++++++---- .../org/wpilib/commands3/SchedulerTest.java | 73 +++++++++++++++++++ 2 files changed, 118 insertions(+), 13 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index d5da2ff720f..8cf9d6697d1 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -567,19 +567,7 @@ private void runCommand(CommandState state) { coroutine.runToYieldPoint(); } catch (RuntimeException e) { // Command encountered an uncaught exception. - // Remove it from the running set. - m_runningCommands.remove(command); - - // Intercept the exception, inject stack frames from the schedule site, and rethrow it - var binding = state.binding(); - e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); - emitCompletedWithErrorEvent(command, e); - // Clean up child commands after emitting the event so child Canceled events are emitted - // after the parent's CompletedWithError - removeOrphanedChildren(command); - - // Then rethrow the exception - throw e; + handleCommandException(state, e); } finally { long endMicros = RobotController.getTime(); double elapsedMs = Milliseconds.convertFrom(endMicros - startMicros, Microseconds); @@ -610,6 +598,50 @@ private void runCommand(CommandState state) { } } + /** + * Handles uncaught runtime exceptions from a mounted and running command. The command's ancestor + * and child commands will all be canceled and the exception's backtrace will be modified to + * include the stack frames of the schedule call site. + * + * @param state The state of the command that encountered the exception. + * @param e The exception that was thrown. + * @throws RuntimeException rethrows the exception, with a modified backtrace pointing to the + * schedule site + */ + @SuppressWarnings("PMD.CompareObjectsWithEquals") + private void handleCommandException(CommandState state, RuntimeException e) { + var command = state.command(); + + // Fetch the root command + // (needs to be done before removing the failed command from the running set) + Command root = command; + while (getParentOf(root) != null) { + root = getParentOf(root); + } + + // Remove it from the running set. + m_runningCommands.remove(command); + + // Intercept the exception, inject stack frames from the schedule site, and rethrow it + var binding = state.binding(); + e.setStackTrace(CommandTraceHelper.modifyTrace(e.getStackTrace(), binding.frames())); + emitCompletedWithErrorEvent(command, e); + + // Clean up child commands after emitting the event so child Canceled events are emitted + // after the parent's CompletedWithError + removeOrphanedChildren(command); + + // Bubble up to the root and cancel all commands between the root and this one + // Note: Because we remove the command from the running set above, we still need to + // clean up all the failed command's children + if (root != null && root != command) { + cancel(root); + } + + // Then rethrow the exception + throw e; + } + /** * Gets the currently executing command state, or null if no command is currently executing. * diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index d522cafb61d..015e91e928b 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -13,6 +13,11 @@ import static org.junit.jupiter.api.Assertions.assertThrowsExactly; import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; +import static org.wpilib.commands3.SchedulerEvent.Canceled; +import static org.wpilib.commands3.SchedulerEvent.CompletedWithError; +import static org.wpilib.commands3.SchedulerEvent.Mounted; +import static org.wpilib.commands3.SchedulerEvent.Scheduled; +import static org.wpilib.commands3.SchedulerEvent.Yielded; import edu.wpi.first.wpilibj.RobotController; import java.util.ArrayList; @@ -31,11 +36,14 @@ @Timeout(5) class SchedulerTest { private Scheduler m_scheduler; + private List m_events; @BeforeEach void setup() { RobotController.setTimeSource(() -> System.nanoTime() / 1000L); m_scheduler = new Scheduler(); + m_events = new ArrayList<>(); + m_scheduler.addEventListener(m_events::add); } @Test @@ -299,6 +307,71 @@ void childCommandEncounteringErrorCancelsParent() { assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); } + @Test + @SuppressWarnings("PMD.CompareObjectsWithEquals") + void childCommandEncounteringErrorAfterRemountCancelsParent() { + var child = + Command.noRequirements() + .executing( + co -> { + co.yield(); + throw new RuntimeException("The exception"); // does not bubble up to the parent + }) + .named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.await(child); + co.park(); // pretend other things would happen after the child + }) + .named("Parent"); + + m_scheduler.schedule(command); + + // first run schedules the child and adds it to the running set + m_scheduler.run(); + + // second run encounters the error in the child + final var error = assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isRunning(command), + "Parent command should have been removed from the scheduler"); + assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); + + // Full event history + assertEquals(9, m_events.size()); + assertTrue( + m_events.get(0) instanceof Scheduled s && s.command() == command, + "First event should be parent scheduled"); + assertTrue( + m_events.get(1) instanceof Mounted m && m.command() == command, + "Second event should be parent mounted"); + assertTrue( + m_events.get(2) instanceof Scheduled s && s.command() == child, + "Third event should be child scheduled"); + assertTrue( + m_events.get(3) instanceof Mounted m && m.command() == child, + "Fourth event should be child mounted"); + assertTrue( + m_events.get(4) instanceof Yielded y && y.command() == child, + "Fifth event should be child yielded"); + assertTrue( + m_events.get(5) instanceof Yielded y && y.command() == command, + "Sixth event should be parent yielded"); + assertTrue( + m_events.get(6) instanceof Mounted m && m.command() == child, + "Seventh event should be child remounted"); + assertTrue( + m_events.get(7) instanceof CompletedWithError c + && c.command() == child + && c.error() == error, + "Eighth event should be child completed with error"); + assertTrue( + m_events.get(8) instanceof Canceled c && c.command() == command, + "Ninth event should be parent canceled"); + } + @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void runMechanism() { From ad925bd5a4461837561b520ab201a0e8d14c8a78 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 4 Sep 2025 18:05:54 -0400 Subject: [PATCH 126/153] Split scheduler tests into separate files for organization A single 1300+ line test file is too hard to keep organized --- .../org/wpilib/commands3/CommandTestBase.java | 23 + .../commands3/ConflictDetectorTest.java | 12 +- .../org/wpilib/commands3/CoroutineTest.java | 12 +- .../wpilib/commands3/ParallelGroupTest.java | 10 +- .../org/wpilib/commands3/PriorityCommand.java | 29 + .../org/wpilib/commands3/SchedulerTest.java | 1170 +---------------- .../commands3/SchedulerTest_Cancellation.java | 375 ++++++ .../commands3/SchedulerTest_Conflicts.java | 163 +++ .../commands3/SchedulerTest_Errors.java | 224 ++++ .../commands3/SchedulerTest_Priorities.java | 69 + .../commands3/SchedulerTest_Sideloads.java | 101 ++ .../commands3/SchedulerTest_Telemetry.java | 115 ++ .../commands3/SchedulerTest_Timing.java | 187 +++ .../wpilib/commands3/SequentialGroupTest.java | 10 +- .../org/wpilib/commands3/TriggerTest.java | 12 +- styleguide/spotbugs-exclude.xml | 10 - 16 files changed, 1293 insertions(+), 1229 deletions(-) create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/PriorityCommand.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java create mode 100644 commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java b/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java new file mode 100644 index 00000000000..9b278e72826 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java @@ -0,0 +1,23 @@ +// 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 org.wpilib.commands3; + +import edu.wpi.first.wpilibj.RobotController; +import java.util.ArrayList; +import java.util.List; +import org.junit.jupiter.api.BeforeEach; + +class CommandTestBase { + protected Scheduler m_scheduler; + protected List m_events; + + @BeforeEach + void initScheduler() { + RobotController.setTimeSource(() -> System.nanoTime() / 1000L); + m_scheduler = new Scheduler(); + m_events = new ArrayList<>(); + m_scheduler.addEventListener(m_events::add); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java index 070efa98a87..ae1e5ef8627 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java @@ -9,22 +9,12 @@ import static org.wpilib.commands3.ConflictDetector.findAllConflicts; import static org.wpilib.commands3.ConflictDetector.throwIfConflicts; -import edu.wpi.first.wpilibj.RobotController; import java.util.List; import java.util.Set; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.wpilib.commands3.ConflictDetector.Conflict; -class ConflictDetectorTest { - private Scheduler m_scheduler; - - @BeforeEach - void setup() { - RobotController.setTimeSource(() -> System.nanoTime() / 1000L); - m_scheduler = new Scheduler(); - } - +class ConflictDetectorTest extends CommandTestBase { @Test void emptyInputHasNoConflicts() { var conflicts = findAllConflicts(List.of()); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index 36d22fb9ffc..9691fb8b507 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -8,25 +8,15 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; -import edu.wpi.first.wpilibj.RobotController; import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; import java.util.concurrent.atomic.AtomicReference; import java.util.concurrent.locks.Lock; import java.util.concurrent.locks.ReentrantLock; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -class CoroutineTest { - Scheduler m_scheduler; - - @BeforeEach - void setup() { - m_scheduler = new Scheduler(); - RobotController.setTimeSource(() -> System.nanoTime() / 1000L); - } - +class CoroutineTest extends CommandTestBase { @Test void forkMany() { var a = new NullCommand(); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 9e1fe9ac8d9..b0189c78b2a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -11,17 +11,9 @@ import java.util.List; import java.util.Set; import java.util.concurrent.atomic.AtomicInteger; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -class ParallelGroupTest { - private Scheduler m_scheduler; - - @BeforeEach - void setup() { - m_scheduler = new Scheduler(); - } - +class ParallelGroupTest extends CommandTestBase { @Test void parallelAll() { var r1 = new Mechanism("R1", m_scheduler); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/PriorityCommand.java b/commandsv3/src/test/java/org/wpilib/commands3/PriorityCommand.java new file mode 100644 index 00000000000..6599b3f8616 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/PriorityCommand.java @@ -0,0 +1,29 @@ +// 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 org.wpilib.commands3; + +import java.util.Set; + +record PriorityCommand(int priority, Mechanism... subsystems) implements Command { + @Override + public void run(Coroutine coroutine) { + coroutine.park(); + } + + @Override + public Set requirements() { + return Set.of(subsystems); + } + + @Override + public String name() { + return toString(); + } + + @Override + public String toString() { + return "PriorityCommand[priority=" + priority + ", subsystems=" + Set.of(subsystems) + "]"; + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 015e91e928b..790db18acf4 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -4,48 +4,15 @@ package org.wpilib.commands3; -import static edu.wpi.first.units.Units.Microseconds; -import static edu.wpi.first.units.Units.Milliseconds; -import static edu.wpi.first.units.Units.Seconds; 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 static org.junit.jupiter.api.Assertions.assertThrowsExactly; import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; -import static org.wpilib.commands3.SchedulerEvent.Canceled; -import static org.wpilib.commands3.SchedulerEvent.CompletedWithError; -import static org.wpilib.commands3.SchedulerEvent.Mounted; -import static org.wpilib.commands3.SchedulerEvent.Scheduled; -import static org.wpilib.commands3.SchedulerEvent.Yielded; -import edu.wpi.first.wpilibj.RobotController; -import java.util.ArrayList; -import java.util.Collections; import java.util.List; -import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; -import java.util.concurrent.atomic.AtomicInteger; -import java.util.concurrent.atomic.AtomicLong; -import java.util.concurrent.atomic.AtomicReference; -import java.util.function.Supplier; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -import org.junit.jupiter.api.Timeout; - -@Timeout(5) -class SchedulerTest { - private Scheduler m_scheduler; - private List m_events; - - @BeforeEach - void setup() { - RobotController.setTimeSource(() -> System.nanoTime() / 1000L); - m_scheduler = new Scheduler(); - m_events = new ArrayList<>(); - m_scheduler.addEventListener(m_events::add); - } +class SchedulerTest extends CommandTestBase { @Test void basic() { var enabled = new AtomicBoolean(false); @@ -74,61 +41,6 @@ void basic() { assertTrue(ran.get()); } - @Test - void higherPriorityCancels() { - final var subsystem = new Mechanism("Subsystem", m_scheduler); - - final var lower = new PriorityCommand(-1000, subsystem); - final var higher = new PriorityCommand(+1000, subsystem); - - m_scheduler.schedule(lower); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(lower)); - - m_scheduler.schedule(higher); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(higher)); - assertFalse(m_scheduler.isRunning(lower)); - } - - @Test - void lowerPriorityDoesNotCancel() { - final var subsystem = new Mechanism("Subsystem", m_scheduler); - - final var lower = new PriorityCommand(-1000, subsystem); - final var higher = new PriorityCommand(+1000, subsystem); - - m_scheduler.schedule(higher); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(higher)); - - m_scheduler.schedule(lower); - m_scheduler.run(); - if (!m_scheduler.isRunning(higher)) { - fail("Higher priority command should still be running"); - } - if (m_scheduler.isRunning(lower)) { - fail("Lower priority command should not be running"); - } - } - - @Test - void samePriorityCancels() { - final var subsystem = new Mechanism("Subsystem", m_scheduler); - - final var first = new PriorityCommand(512, subsystem); - final var second = new PriorityCommand(512, subsystem); - - m_scheduler.schedule(first); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(first)); - - m_scheduler.schedule(second); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(second), "New command should be running"); - assertFalse(m_scheduler.isRunning(first), "Old command should be canceled"); - } - @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void atomicity() { @@ -150,8 +62,8 @@ void atomicity() { .executing( coroutine -> { for (int i = 0; i < iterations; i++) { - coroutine.yield(); mechanism.m_x++; + coroutine.yield(); } }) .named("CountCommand[" + cmdCount + "]"); @@ -162,216 +74,10 @@ void atomicity() { for (int i = 0; i < iterations; i++) { m_scheduler.run(); } - m_scheduler.run(); assertEquals(numCommands * iterations, mechanism.m_x); } - @Test - @SuppressWarnings("PMD.AvoidCatchingGenericException") - void errorDetection() { - var mechanism = new Mechanism("X", m_scheduler); - - var command = - mechanism - .run( - coroutine -> { - throw new RuntimeException("The exception"); - }) - .named("Bad Behavior"); - - new Trigger(m_scheduler, () -> true).onTrue(command); - - try { - m_scheduler.run(); - fail("An exception should have been thrown"); - } catch (RuntimeException e) { - assertEquals("The exception", e.getMessage()); - - assertEquals("org.wpilib.commands3.SchedulerTest", e.getStackTrace()[0].getClassName()); - assertEquals("lambda$errorDetection$3", e.getStackTrace()[0].getMethodName()); - - assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); - - assertEquals(getClass().getName(), e.getStackTrace()[3].getClassName()); - assertEquals("errorDetection", e.getStackTrace()[3].getMethodName()); - } catch (Throwable t) { - fail("Expected a RuntimeException to be thrown, but got " + t); - } - } - - @Test - void nestedErrorDetection() { - var command = - Command.noRequirements() - .executing( - co -> { - co.await( - Command.noRequirements() - .executing( - c2 -> { - new Trigger(m_scheduler, () -> true) - .onTrue( - Command.noRequirements() - .executing( - c3 -> { - // Throws IndexOutOfBoundsException - new ArrayList<>(0).get(-1); - }) - .named("Throws IndexOutOfBounds")); - c2.park(); - }) - .named("Schedules With Trigger")); - }) - .named("Schedules Directly"); - - m_scheduler.schedule(command); - - // The first run sets up the trigger, but does not fire - // The second run will fire the trigger and cause the inner command to run and throw - m_scheduler.run(); - - try { - m_scheduler.run(); - fail("Index OOB exception expected"); - } catch (IndexOutOfBoundsException e) { - StackTraceElement[] stackTrace = e.getStackTrace(); - - assertEquals("Index -1 out of bounds for length 0", e.getMessage()); - int nestedIndex = 0; - for (; nestedIndex < stackTrace.length; nestedIndex++) { - if (stackTrace[nestedIndex].getClassName().equals(getClass().getName())) { - break; - } - } - - // user code trace for the scheduler run invocation (to `scheduler.run()` in the try block) - assertEquals("lambda$nestedErrorDetection$6", stackTrace[nestedIndex].getMethodName()); - assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 1].getMethodName()); - - // user code trace for where the command was scheduled (the `.onTrue()` line) - assertEquals("=== Command Binding Trace ===", stackTrace[nestedIndex + 2].getClassName()); - assertEquals("lambda$nestedErrorDetection$7", stackTrace[nestedIndex + 3].getMethodName()); - assertEquals("lambda$nestedErrorDetection$8", stackTrace[nestedIndex + 4].getMethodName()); - assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 5].getMethodName()); - } catch (Throwable unexpected) { - fail("Expected an IndexOutOfBoundsException to have been thrown, but got" + unexpected); - } - } - - @Test - void commandEncounteringErrorCancelsChildren() { - var child = Command.noRequirements().executing(Coroutine::park).named("Child 1"); - var command = - Command.noRequirements() - .executing( - co -> { - co.fork(child); - throw new RuntimeException("The exception"); - }) - .named("Bad Behavior"); - - m_scheduler.schedule(command); - assertThrows(RuntimeException.class, m_scheduler::run); - assertFalse( - m_scheduler.isScheduledOrRunning(command), - "Command should have been removed from the scheduler"); - assertFalse( - m_scheduler.isScheduledOrRunning(child), - "Child should have been removed from the scheduler"); - } - - @Test - void childCommandEncounteringErrorCancelsParent() { - var child = - Command.noRequirements() - .executing( - co -> { - throw new RuntimeException("The exception"); // note: bubbles up to the parent - }) - .named("Child 1"); - var command = - Command.noRequirements() - .executing( - co -> { - co.await(child); - co.park(); // pretend other things would happen after the child - }) - .named("Parent"); - - m_scheduler.schedule(command); - assertThrows(RuntimeException.class, m_scheduler::run); - assertFalse( - m_scheduler.isRunning(command), - "Parent command should have been removed from the scheduler"); - assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); - } - - @Test - @SuppressWarnings("PMD.CompareObjectsWithEquals") - void childCommandEncounteringErrorAfterRemountCancelsParent() { - var child = - Command.noRequirements() - .executing( - co -> { - co.yield(); - throw new RuntimeException("The exception"); // does not bubble up to the parent - }) - .named("Child 1"); - var command = - Command.noRequirements() - .executing( - co -> { - co.await(child); - co.park(); // pretend other things would happen after the child - }) - .named("Parent"); - - m_scheduler.schedule(command); - - // first run schedules the child and adds it to the running set - m_scheduler.run(); - - // second run encounters the error in the child - final var error = assertThrows(RuntimeException.class, m_scheduler::run); - assertFalse( - m_scheduler.isRunning(command), - "Parent command should have been removed from the scheduler"); - assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); - - // Full event history - assertEquals(9, m_events.size()); - assertTrue( - m_events.get(0) instanceof Scheduled s && s.command() == command, - "First event should be parent scheduled"); - assertTrue( - m_events.get(1) instanceof Mounted m && m.command() == command, - "Second event should be parent mounted"); - assertTrue( - m_events.get(2) instanceof Scheduled s && s.command() == child, - "Third event should be child scheduled"); - assertTrue( - m_events.get(3) instanceof Mounted m && m.command() == child, - "Fourth event should be child mounted"); - assertTrue( - m_events.get(4) instanceof Yielded y && y.command() == child, - "Fifth event should be child yielded"); - assertTrue( - m_events.get(5) instanceof Yielded y && y.command() == command, - "Sixth event should be parent yielded"); - assertTrue( - m_events.get(6) instanceof Mounted m && m.command() == child, - "Seventh event should be child remounted"); - assertTrue( - m_events.get(7) instanceof CompletedWithError c - && c.command() == child - && c.error() == error, - "Eighth event should be child completed with error"); - assertTrue( - m_events.get(8) instanceof Canceled c && c.command() == command, - "Ninth event should be parent canceled"); - } - @Test @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs void runMechanism() { @@ -401,274 +107,6 @@ void runMechanism() { assertEquals(10, example.m_x); } - @Test - void cancelOnInterruptDoesNotResume() { - var count = new AtomicInteger(0); - - var mechanism = new Mechanism("mechanism", m_scheduler); - - var interrupter = - Command.requiring(mechanism) - .executing(coroutine -> {}) - .withPriority(2) - .named("Interrupter"); - - var canceledCommand = - Command.requiring(mechanism) - .executing( - coroutine -> { - count.set(1); - coroutine.yield(); - count.set(2); - }) - .withPriority(1) - .named("Cancel By Default"); - - m_scheduler.schedule(canceledCommand); - m_scheduler.run(); - - m_scheduler.schedule(interrupter); - m_scheduler.run(); - assertEquals(1, count.get()); // the second "set" call should not have run - } - - @Test - void scheduleOverDefaultDoesNotRescheduleDefault() { - var count = new AtomicInteger(0); - - var mechanism = new Mechanism("mechanism", m_scheduler); - var defaultCmd = - mechanism - .run( - coroutine -> { - while (true) { - count.incrementAndGet(); - coroutine.yield(); - } - }) - .withPriority(-1) - .named("Default Command"); - - final var newerCmd = mechanism.run(coroutine -> {}).named("Newer Command"); - mechanism.setDefaultCommand(defaultCmd); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(defaultCmd), "Default command should be running"); - - m_scheduler.schedule(newerCmd); - m_scheduler.run(); - assertFalse(m_scheduler.isRunning(defaultCmd), "Default command should have been interrupted"); - assertEquals(1, count.get(), "Default command should have run once"); - - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(defaultCmd)); - } - - @Test - void cancelsEvictsOnDeck() { - var command = Command.noRequirements().executing(Coroutine::park).named("Command"); - m_scheduler.schedule(command); - m_scheduler.cancel(command); - assertFalse(m_scheduler.isScheduledOrRunning(command)); - } - - @Test - void commandCancelingSelf() { - var ranAfterCancel = new AtomicBoolean(false); - var commandRef = new AtomicReference(null); - var command = - Command.noRequirements() - .executing( - co -> { - co.scheduler().cancel(commandRef.get()); - ranAfterCancel.set(true); - }) - .named("Command"); - commandRef.set(command); - m_scheduler.schedule(command); - - var error = assertThrows(IllegalArgumentException.class, () -> m_scheduler.run()); - assertEquals("Command `Command` is mounted and cannot be canceled", error.getMessage()); - assertFalse(ranAfterCancel.get(), "Command should have stopped after encountering an error"); - assertFalse( - m_scheduler.isScheduledOrRunning(command), - "Command should have been removed from the scheduler"); - } - - @Test - void cancelAllEvictsOnDeck() { - var command = Command.noRequirements().executing(Coroutine::park).named("Command"); - m_scheduler.schedule(command); - m_scheduler.cancelAll(); - assertFalse(m_scheduler.isScheduledOrRunning(command)); - } - - @Test - void cancelAllCancelsAll() { - var commands = new ArrayList(10); - for (int i = 1; i <= 10; i++) { - commands.add(Command.noRequirements().executing(Coroutine::yield).named("Command " + i)); - } - commands.forEach(m_scheduler::schedule); - m_scheduler.run(); - m_scheduler.cancelAll(); - for (Command command : commands) { - if (m_scheduler.isRunning(command)) { - fail(command.name() + " was not canceled by cancelAll()"); - } - } - } - - @Test - void cancelAllCallsOnCancelHookForRunningCommands() { - AtomicBoolean ranHook = new AtomicBoolean(false); - var command = - Command.noRequirements() - .executing(Coroutine::park) - .whenCanceled(() -> ranHook.set(true)) - .named("Command"); - m_scheduler.schedule(command); - m_scheduler.run(); - m_scheduler.cancelAll(); - assertTrue(ranHook.get(), "onCancel hook was not called"); - } - - @Test - void cancelAllDoesNotCallOnCancelHookForQueuedCommands() { - AtomicBoolean ranHook = new AtomicBoolean(false); - var command = - Command.noRequirements() - .executing(Coroutine::park) - .whenCanceled(() -> ranHook.set(true)) - .named("Command"); - m_scheduler.schedule(command); - // no call to run before cancelAll() - m_scheduler.cancelAll(); - assertFalse(ranHook.get(), "onCancel hook was not called"); - } - - @Test - void cancelAllStartsDefaults() { - var mechanisms = new ArrayList(10); - for (int i = 1; i <= 10; i++) { - mechanisms.add(new Mechanism("System " + i, m_scheduler)); - } - - var command = Command.requiring(mechanisms).executing(Coroutine::yield).named("Big Command"); - - // Scheduling the command should evict the on-deck default commands - m_scheduler.schedule(command); - - // Then running should get it into the set of running commands - m_scheduler.run(); - - // Canceling should clear out the set of running commands - m_scheduler.cancelAll(); - - // Then ticking the scheduler once to fully remove the command and schedule the defaults - m_scheduler.run(); - - // Then one more tick to start running the scheduled defaults - m_scheduler.run(); - - if (m_scheduler.isRunning(command)) { - System.err.println(m_scheduler.getRunningCommands()); - fail(command.name() + " was not canceled by cancelAll()"); - } - - for (var mechanism : mechanisms) { - var runningCommands = m_scheduler.getRunningCommandsFor(mechanism); - assertEquals( - 1, - runningCommands.size(), - "mechanism " + mechanism + " should have exactly one running command"); - assertEquals( - mechanism.getDefaultCommand(), - runningCommands.getFirst(), - "mechanism " + mechanism + " is not running the default command"); - } - } - - @Test - void cancelDeeplyNestedCompositions() { - Command root = - Command.noRequirements() - .executing( - co -> { - co.await( - Command.noRequirements() - .executing( - co2 -> { - co2.await( - Command.noRequirements() - .executing( - co3 -> { - co3.await( - Command.noRequirements() - .executing(Coroutine::park) - .named("Park")); - }) - .named("C3")); - }) - .named("C2")); - }) - .named("Root"); - - m_scheduler.schedule(root); - - m_scheduler.run(); - assertEquals(4, m_scheduler.getRunningCommands().size()); - - m_scheduler.cancel(root); - assertEquals(0, m_scheduler.getRunningCommands().size()); - } - - @Test - void compositionsDoNotSelfCancel() { - var mech = new Mechanism("The mechanism", m_scheduler); - var group = - mech.run( - co -> { - co.await( - mech.run( - co2 -> { - co2.await( - mech.run( - co3 -> { - co3.await(mech.run(Coroutine::park).named("Park")); - }) - .named("C3")); - }) - .named("C2")); - }) - .named("Group"); - - m_scheduler.schedule(group); - m_scheduler.run(); - assertEquals(4, m_scheduler.getRunningCommands().size()); - assertTrue(m_scheduler.isRunning(group)); - } - - @Test - void compositionsDoNotCancelParent() { - var mech = new Mechanism("The mechanism", m_scheduler); - var group = - mech.run( - co -> { - co.fork(mech.run(Coroutine::park).named("First Child")); - co.fork(mech.run(Coroutine::park).named("Second Child")); - co.park(); - }) - .named("Group"); - - m_scheduler.schedule(group); - m_scheduler.run(); - - // second child interrupts first child - assertEquals( - List.of("Group", "Second Child"), - m_scheduler.getRunningCommands().stream().map(Command::name).toList()); - } - @Test void compositionsDoNotNeedRequirements() { var m1 = new Mechanism("M1", m_scheduler); @@ -690,199 +128,6 @@ void compositionsDoNotNeedRequirements() { assertEquals(3, m_scheduler.getRunningCommands().size()); } - @Test - void compositionsCannotAwaitConflictingCommands() { - var mech = new Mechanism("The Mechanism", m_scheduler); - - var group = - Command.noRequirements() - .executing( - co -> { - co.awaitAll( - mech.run(Coroutine::park).named("First"), - mech.run(Coroutine::park).named("Second")); - }) - .named("Group"); - - m_scheduler.schedule(group); - - // Running should attempt to schedule multiple conflicting commands - var exception = assertThrows(IllegalArgumentException.class, m_scheduler::run); - assertEquals( - "Commands running in parallel cannot share requirements: " - + "First and Second both require The Mechanism", - exception.getMessage()); - } - - @Test - void doesNotRunOnCancelWhenInterruptingOnDeck() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - var interrupter = mechanism.run(Coroutine::yield).named("Interrupter"); - m_scheduler.schedule(cmd); - m_scheduler.schedule(interrupter); - m_scheduler.run(); - - assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); - } - - @Test - void doesNotRunOnCancelWhenCancelingOnDeck() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - m_scheduler.schedule(cmd); - // canceling before calling .run() - m_scheduler.cancel(cmd); - m_scheduler.run(); - - assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); - } - - @Test - void runsOnCancelWhenInterruptingCommand() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); - var interrupter = mechanism.run(Coroutine::park).named("Interrupter"); - m_scheduler.schedule(cmd); - m_scheduler.run(); - m_scheduler.schedule(interrupter); - m_scheduler.run(); - - assertTrue(ran.get(), "onCancel should have run!"); - } - - @Test - void doesNotRunOnCancelWhenCompleting() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - m_scheduler.schedule(cmd); - m_scheduler.run(); - m_scheduler.run(); - - assertFalse(m_scheduler.isScheduledOrRunning(cmd)); - assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); - } - - @Test - void runsOnCancelWhenCanceling() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - m_scheduler.schedule(cmd); - m_scheduler.run(); - m_scheduler.cancel(cmd); - - assertTrue(ran.get(), "onCancel should have run!"); - } - - @Test - void runsOnCancelWhenCancelingParent() { - var ran = new AtomicBoolean(false); - - var mechanism = new Mechanism("The mechanism", m_scheduler); - var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); - - var group = new SequentialGroup("Seq", Collections.singletonList(cmd)); - m_scheduler.schedule(group); - m_scheduler.run(); - m_scheduler.cancel(group); - - assertTrue(ran.get(), "onCancel should have run!"); - } - - @Test - void sideloadThrowingException() { - m_scheduler.sideload( - co -> { - throw new RuntimeException("Bang!"); - }); - - // An exception raised in a sideload function should bubble up - assertEquals( - "Bang!", assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); - } - - @Test - void periodicSideload() { - AtomicInteger count = new AtomicInteger(0); - m_scheduler.addPeriodic(count::incrementAndGet); - assertEquals(0, count.get()); - - m_scheduler.run(); - assertEquals(1, count.get()); - - m_scheduler.run(); - assertEquals(2, count.get()); - } - - @Test - void sideloadSchedulingCommand() { - var command = Command.noRequirements().executing(Coroutine::park).named("Command"); - // one-shot sideload forks a command and immediately exits - m_scheduler.sideload(co -> co.fork(command)); - m_scheduler.run(); - assertTrue( - m_scheduler.isRunning(command), "command should have started and outlasted the sideload"); - } - - @Test - void childCommandEscapesViaSideload() { - var child = Command.noRequirements().executing(Coroutine::park).named("Child"); - var parent = - Command.noRequirements() - .executing( - parentCoroutine -> { - m_scheduler.sideload(sidelodCoroutine -> sidelodCoroutine.fork(child)); - }) - .named("Parent"); - - m_scheduler.schedule(parent); - m_scheduler.run(); - assertFalse(m_scheduler.isScheduledOrRunning(parent), "parent should have exited"); - assertFalse( - m_scheduler.isScheduledOrRunning(child), - "the sideload to schedule the child should not have run yet"); - - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(child), "child should have started running"); - } - - @Test - void sideloadCancelingCommand() { - var command = Command.noRequirements().executing(Coroutine::park).named("Command"); - m_scheduler.schedule(command); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(command), "command should have started"); - - m_scheduler.sideload(co -> m_scheduler.cancel(command)); - assertTrue(m_scheduler.isRunning(command), "sideload should not have run yet"); - - m_scheduler.run(); - assertFalse(m_scheduler.isRunning(command), "sideload should have canceled the command"); - } - - @Test - void sideloadAffectsStateForTriggerInSameCycle() { - AtomicBoolean signal = new AtomicBoolean(false); - var trigger = new Trigger(m_scheduler, signal::get); - var command = Command.noRequirements().executing(Coroutine::park).named("Command"); - trigger.onTrue(command); - m_scheduler.sideload(co -> signal.set(true)); - - m_scheduler.run(); - assertTrue(signal.get(), "Sideload should have run and set the signal"); - assertTrue(m_scheduler.isRunning(command), "Command should have started"); - } - @Test void nestedMechanisms() { var superstructure = @@ -913,415 +158,4 @@ public Command superCommand() { m_scheduler.run(); // starts running the default superstructure command assertEquals(List.of(superstructure.getDefaultCommand()), superstructure.getRunningCommands()); } - - @Test - void protobuf() { - var mech = new Mechanism("The mechanism", m_scheduler); - var parkCommand = mech.run(Coroutine::park).named("Park"); - var c3Command = mech.run(co -> co.await(parkCommand)).named("C3"); - var c2Command = mech.run(co -> co.await(c3Command)).named("C2"); - var group = mech.run(co -> co.await(c2Command)).named("Group"); - - m_scheduler.schedule(group); - m_scheduler.run(); - - var scheduledCommand1 = Command.noRequirements().executing(Coroutine::park).named("Command 1"); - var scheduledCommand2 = Command.noRequirements().executing(Coroutine::park).named("Command 2"); - m_scheduler.schedule(scheduledCommand1); - m_scheduler.schedule(scheduledCommand2); - - var message = Scheduler.proto.createMessage(); - Scheduler.proto.pack(message, m_scheduler); - var messageJson = message.toString(); - assertEquals( - """ - { - "lastTimeMs": %s, - "queuedCommands": [{ - "priority": 0, - "id": %s, - "name": "Command 1" - }, { - "priority": 0, - "id": %s, - "name": "Command 2" - }], - "runningCommands": [{ - "lastTimeMs": %s, - "totalTimeMs": %s, - "priority": 0, - "id": %s, - "name": "Group", - "requirements": [{ - "name": "The mechanism" - }] - }, { - "lastTimeMs": %s, - "totalTimeMs": %s, - "priority": 0, - "id": %s, - "parentId": %s, - "name": "C2", - "requirements": [{ - "name": "The mechanism" - }] - }, { - "lastTimeMs": %s, - "totalTimeMs": %s, - "priority": 0, - "id": %s, - "parentId": %s, - "name": "C3", - "requirements": [{ - "name": "The mechanism" - }] - }, { - "lastTimeMs": %s, - "totalTimeMs": %s, - "priority": 0, - "id": %s, - "parentId": %s, - "name": "Park", - "requirements": [{ - "name": "The mechanism" - }] - }] - }""" - .formatted( - // Scheduler data - m_scheduler.lastRuntimeMs(), - - // On deck commands - m_scheduler.runId(scheduledCommand1), - m_scheduler.runId(scheduledCommand2), - - // Running commands - m_scheduler.lastCommandRuntimeMs(group), - m_scheduler.totalRuntimeMs(group), - m_scheduler.runId(group), // id - // top-level command, no parent ID - - m_scheduler.lastCommandRuntimeMs(c2Command), - m_scheduler.totalRuntimeMs(c2Command), - m_scheduler.runId(c2Command), // id - m_scheduler.runId(group), // parent - m_scheduler.lastCommandRuntimeMs(c3Command), - m_scheduler.totalRuntimeMs(c3Command), - m_scheduler.runId(c3Command), // id - m_scheduler.runId(c2Command), // parent - m_scheduler.lastCommandRuntimeMs(parkCommand), - m_scheduler.totalRuntimeMs(parkCommand), - m_scheduler.runId(parkCommand), // id - m_scheduler.runId(c3Command) // parent - ), - messageJson); - } - - @Test - void siblingsInCompositionCanShareRequirements() { - var mechanism = new Mechanism("The mechanism", m_scheduler); - var firstRan = new AtomicBoolean(false); - var secondRan = new AtomicBoolean(false); - - var first = - mechanism - .run( - c -> { - firstRan.set(true); - c.park(); - }) - .named("First"); - - var second = - mechanism - .run( - c -> { - secondRan.set(true); - c.park(); - }) - .named("Second"); - - var group = - Command.noRequirements() - .executing( - co -> { - co.fork(first); - co.fork(second); - co.park(); - }) - .named("Group"); - - m_scheduler.schedule(group); - m_scheduler.run(); - - assertTrue(firstRan.get(), "First child should have run to a yield point"); - assertTrue(secondRan.get(), "Second child should have run to a yield point"); - assertFalse( - m_scheduler.isScheduledOrRunning(first), "First child should have been interrupted"); - assertTrue(m_scheduler.isRunning(second), "Second child should still be running"); - assertTrue(m_scheduler.isRunning(group), "Group should still be running"); - } - - @Test - void nestedOneShotCompositionsAllRunInOneCycle() { - var runs = new AtomicInteger(0); - Supplier makeOneShot = - () -> Command.noRequirements().executing(_c -> runs.incrementAndGet()).named("One Shot"); - var command = - Command.noRequirements() - .executing( - co -> { - co.fork(makeOneShot.get()); - co.fork(makeOneShot.get()); - co.fork( - Command.noRequirements() - .executing(inner -> inner.fork(makeOneShot.get())) - .named("Inner")); - co.fork( - Command.noRequirements() - .executing( - co2 -> { - co2.fork(makeOneShot.get()); - co2.fork( - Command.noRequirements() - .executing( - co3 -> { - co3.fork(makeOneShot.get()); - }) - .named("3")); - }) - .named("2")); - }) - .named("Command"); - - m_scheduler.schedule(command); - m_scheduler.run(); - assertEquals(5, runs.get(), "All oneshot commands should have run"); - assertFalse(m_scheduler.isRunning(command), "Command should have exited after one cycle"); - } - - @Test - void childConflictsWithHigherPriorityTopLevel() { - var mechanism = new Mechanism("mechanism", m_scheduler); - var top = mechanism.run(Coroutine::park).withPriority(10).named("Top"); - - // Child conflicts with and is lower priority than the Top command - // It should not be scheduled, and the parent command should exit immediately - var child = mechanism.run(Coroutine::park).named("Child"); - var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent"); - - m_scheduler.schedule(top); - m_scheduler.schedule(parent); - m_scheduler.run(); - - assertTrue(m_scheduler.isRunning(top), "Top command should not have been interrupted"); - assertFalse(m_scheduler.isRunning(child), "Conflicting child should not have run"); - assertFalse(m_scheduler.isRunning(parent), "Parent of conflicting child should have exited"); - } - - @Test - void childConflictsWithLowerPriorityTopLevel() { - var mechanism = new Mechanism("mechanism", m_scheduler); - var top = mechanism.run(Coroutine::park).withPriority(-10).named("Top"); - - // Child conflicts with and is lower priority than the Top command - // It should not be scheduled, and the parent command should exit immediately - var child = mechanism.run(Coroutine::park).named("Child"); - var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent"); - - m_scheduler.schedule(top); - m_scheduler.schedule(parent); - m_scheduler.run(); - - assertFalse(m_scheduler.isRunning(top), "Top command should have been interrupted"); - assertTrue(m_scheduler.isRunning(child), "Conflicting child should be running"); - assertTrue(m_scheduler.isRunning(parent), "Parent of conflicting child should be running"); - } - - @Test - void commandAwaitingItself() { - // This command deadlocks on itself. It's calling yield() in an infinite loop, which is - // equivalent to calling Coroutine.park(). No deleterious side effects other than stalling - // the command - AtomicReference commandRef = new AtomicReference<>(); - var command = - Command.noRequirements().executing(co -> co.await(commandRef.get())).named("Self Await"); - commandRef.set(command); - - m_scheduler.schedule(command); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(command)); - } - - @Test - void commandDeadlock() { - AtomicReference ref1 = new AtomicReference<>(); - AtomicReference ref2 = new AtomicReference<>(); - - // Deadlock scenario: - // command1 starts, schedules command2, then waits for command2 to exit - // command2 starts, waits for command1 to exit - // - // Each successive run sees command1 mount, check for command2, then yield. - // Then sees command2 mount, check for command1, then also yield. - // This is like two threads spinwaiting for the other to exit. - // - // Externally canceling command2 allows command1 to continue - // Externally canceling command1 cancels both - var command1 = - Command.noRequirements().executing(co -> co.await(ref2.get())).named("Command 1"); - var command2 = - Command.noRequirements().executing(co -> co.await(ref1.get())).named("Command 2"); - ref1.set(command1); - ref2.set(command2); - - m_scheduler.schedule(command1); - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(command1)); - assertTrue(m_scheduler.isRunning(command2)); - - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(command1)); - assertTrue(m_scheduler.isRunning(command2)); - - m_scheduler.cancel(command1); - m_scheduler.run(); - assertFalse(m_scheduler.isRunning(command1)); - assertFalse(m_scheduler.isRunning(command2)); - } - - @Test - void forkedChildRunsOnce() { - AtomicInteger runCount = new AtomicInteger(0); - - var inner = - Command.noRequirements() - .executing( - co -> { - runCount.incrementAndGet(); - co.yield(); - - runCount.incrementAndGet(); - co.yield(); - }) - .named("Inner"); - - var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); - m_scheduler.schedule(outer); - m_scheduler.run(); - - assertEquals(1, runCount.get()); - } - - @Test - void shortWaitWaitsOneLoop() { - AtomicLong time = new AtomicLong(0); - RobotController.setTimeSource(time::get); - - AtomicBoolean completedWait = new AtomicBoolean(false); - var command = - Command.noRequirements() - .executing( - co -> { - co.wait(Milliseconds.of(1)); - completedWait.set(true); - }) - .named("Short Wait"); - - m_scheduler.schedule(command); - m_scheduler.run(); - - // wait 1 full second (much longer than the wait period) - time.set((long) Seconds.of(1).in(Microseconds)); - m_scheduler.run(); - assertTrue( - completedWait.get(), - "Command with a short wait should have completed if its duration has elapsed between runs"); - } - - @Test - void shortWaitWaitsOneLoopWithFastPeriod() { - AtomicLong time = new AtomicLong(0); - RobotController.setTimeSource(time::get); - AtomicBoolean completedWait = new AtomicBoolean(false); - var command = - Command.noRequirements() - .executing( - co -> { - co.wait(Milliseconds.of(1)); - completedWait.set(true); - }) - .named("Short Wait"); - - m_scheduler.schedule(command); - m_scheduler.run(); - - // move forward by half the wait period - time.set((long) Milliseconds.of(0.5).in(Microseconds)); - m_scheduler.run(); - assertFalse(completedWait.get(), "Command should still be waiting for 1 ms to elapse"); - - // move forward by the rest of the wait period - time.set((long) Milliseconds.of(1).in(Microseconds)); - m_scheduler.run(); - assertTrue( - completedWait.get(), - "Command with a short wait should have completed if its duration has elapsed between runs"); - } - - @Test - void awaitingExitsImmediatelyWithoutAOneLoopDelay() { - AtomicInteger innerRuns = new AtomicInteger(0); - var inner = - Command.noRequirements() - .executing( - co -> { - // executed immediately when forked - innerRuns.incrementAndGet(); - co.yield(); - - // executed again on the next scheduler run, after the forking command runs - innerRuns.incrementAndGet(); - }) - .named("Inner"); - - var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); - m_scheduler.schedule(outer); // schedules inner - - // First run: runs outer, forks inner, inner runs to its first yield, outer yields - m_scheduler.run(); - assertTrue(m_scheduler.isRunning(inner)); - assertTrue(m_scheduler.isRunning(outer)); - assertEquals(1, innerRuns.get()); - - // Second run: runs inner to completion, runs outer, outer sees inner is complete and exits - // NOTE: If child commands ran AFTER their parents, then outer would not have exited here and - // would take another scheduler run to complete - m_scheduler.run(); - assertFalse(m_scheduler.isRunning(inner)); - assertFalse(m_scheduler.isRunning(outer)); - assertEquals(2, innerRuns.get()); - } - - record PriorityCommand(int priority, Mechanism... subsystems) implements Command { - @Override - public void run(Coroutine coroutine) { - coroutine.park(); - } - - @Override - public Set requirements() { - return Set.of(subsystems); - } - - @Override - public String name() { - return toString(); - } - - @Override - public String toString() { - return "PriorityCommand[priority=" + priority + ", subsystems=" + Set.of(subsystems) + "]"; - } - } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java new file mode 100644 index 00000000000..949833cd11d --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java @@ -0,0 +1,375 @@ +// 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 org.wpilib.commands3; + +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 static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; + +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Cancellation extends CommandTestBase { + @Test + void cancelOnInterruptDoesNotResume() { + var count = new AtomicInteger(0); + + var mechanism = new Mechanism("mechanism", m_scheduler); + + var interrupter = + Command.requiring(mechanism) + .executing(coroutine -> {}) + .withPriority(2) + .named("Interrupter"); + + var canceledCommand = + Command.requiring(mechanism) + .executing( + coroutine -> { + count.set(1); + coroutine.yield(); + count.set(2); + }) + .withPriority(1) + .named("Cancel By Default"); + + m_scheduler.schedule(canceledCommand); + m_scheduler.run(); + + m_scheduler.schedule(interrupter); + m_scheduler.run(); + assertEquals(1, count.get()); // the second "set" call should not have run + } + + @Test + void scheduleOverDefaultDoesNotRescheduleDefault() { + var count = new AtomicInteger(0); + + var mechanism = new Mechanism("mechanism", m_scheduler); + var defaultCmd = + mechanism + .run( + coroutine -> { + while (true) { + count.incrementAndGet(); + coroutine.yield(); + } + }) + .withPriority(-1) + .named("Default Command"); + + final var newerCmd = mechanism.run(coroutine -> {}).named("Newer Command"); + mechanism.setDefaultCommand(defaultCmd); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(defaultCmd), "Default command should be running"); + + m_scheduler.schedule(newerCmd); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(defaultCmd), "Default command should have been interrupted"); + assertEquals(1, count.get(), "Default command should have run once"); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(defaultCmd)); + } + + @Test + void cancelsEvictsOnDeck() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.cancel(command); + assertFalse(m_scheduler.isScheduledOrRunning(command)); + } + + @Test + void commandCancelingSelf() { + var ranAfterCancel = new AtomicBoolean(false); + var commandRef = new AtomicReference(null); + var command = + Command.noRequirements() + .executing( + co -> { + co.scheduler().cancel(commandRef.get()); + ranAfterCancel.set(true); + }) + .named("Command"); + commandRef.set(command); + m_scheduler.schedule(command); + + var error = assertThrows(IllegalArgumentException.class, () -> m_scheduler.run()); + assertEquals("Command `Command` is mounted and cannot be canceled", error.getMessage()); + assertFalse(ranAfterCancel.get(), "Command should have stopped after encountering an error"); + assertFalse( + m_scheduler.isScheduledOrRunning(command), + "Command should have been removed from the scheduler"); + } + + @Test + void cancelAllEvictsOnDeck() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.cancelAll(); + assertFalse(m_scheduler.isScheduledOrRunning(command)); + } + + @Test + void cancelAllCancelsAll() { + var commands = new ArrayList(10); + for (int i = 1; i <= 10; i++) { + commands.add(Command.noRequirements().executing(Coroutine::yield).named("Command " + i)); + } + commands.forEach(m_scheduler::schedule); + m_scheduler.run(); + m_scheduler.cancelAll(); + for (Command command : commands) { + if (m_scheduler.isRunning(command)) { + fail(command.name() + " was not canceled by cancelAll()"); + } + } + } + + @Test + void cancelAllCallsOnCancelHookForRunningCommands() { + AtomicBoolean ranHook = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing(Coroutine::park) + .whenCanceled(() -> ranHook.set(true)) + .named("Command"); + m_scheduler.schedule(command); + m_scheduler.run(); + m_scheduler.cancelAll(); + assertTrue(ranHook.get(), "onCancel hook was not called"); + } + + @Test + void cancelAllDoesNotCallOnCancelHookForQueuedCommands() { + AtomicBoolean ranHook = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing(Coroutine::park) + .whenCanceled(() -> ranHook.set(true)) + .named("Command"); + m_scheduler.schedule(command); + // no call to run before cancelAll() + m_scheduler.cancelAll(); + assertFalse(ranHook.get(), "onCancel hook was not called"); + } + + @Test + void cancelAllStartsDefaults() { + var mechanisms = new ArrayList(10); + for (int i = 1; i <= 10; i++) { + mechanisms.add(new Mechanism("System " + i, m_scheduler)); + } + + var command = Command.requiring(mechanisms).executing(Coroutine::yield).named("Big Command"); + + // Scheduling the command should evict the on-deck default commands + m_scheduler.schedule(command); + + // Then running should get it into the set of running commands + m_scheduler.run(); + + // Canceling should clear out the set of running commands + m_scheduler.cancelAll(); + + // Then ticking the scheduler once to fully remove the command and schedule the defaults + m_scheduler.run(); + + // Then one more tick to start running the scheduled defaults + m_scheduler.run(); + + if (m_scheduler.isRunning(command)) { + System.err.println(m_scheduler.getRunningCommands()); + fail(command.name() + " was not canceled by cancelAll()"); + } + + for (var mechanism : mechanisms) { + var runningCommands = m_scheduler.getRunningCommandsFor(mechanism); + assertEquals( + 1, + runningCommands.size(), + "mechanism " + mechanism + " should have exactly one running command"); + assertEquals( + mechanism.getDefaultCommand(), + runningCommands.getFirst(), + "mechanism " + mechanism + " is not running the default command"); + } + } + + @Test + void cancelDeeplyNestedCompositions() { + Command root = + Command.noRequirements() + .executing( + co -> { + co.await( + Command.noRequirements() + .executing( + co2 -> { + co2.await( + Command.noRequirements() + .executing( + co3 -> { + co3.await( + Command.noRequirements() + .executing(Coroutine::park) + .named("Park")); + }) + .named("C3")); + }) + .named("C2")); + }) + .named("Root"); + + m_scheduler.schedule(root); + + m_scheduler.run(); + assertEquals(4, m_scheduler.getRunningCommands().size()); + + m_scheduler.cancel(root); + assertEquals(0, m_scheduler.getRunningCommands().size()); + } + + @Test + void compositionsDoNotSelfCancel() { + var mech = new Mechanism("The mechanism", m_scheduler); + var group = + mech.run( + co -> { + co.await( + mech.run( + co2 -> { + co2.await( + mech.run( + co3 -> { + co3.await(mech.run(Coroutine::park).named("Park")); + }) + .named("C3")); + }) + .named("C2")); + }) + .named("Group"); + + m_scheduler.schedule(group); + m_scheduler.run(); + assertEquals(4, m_scheduler.getRunningCommands().size()); + assertTrue(m_scheduler.isRunning(group)); + } + + @Test + void compositionsDoNotCancelParent() { + var mech = new Mechanism("The mechanism", m_scheduler); + var group = + mech.run( + co -> { + co.fork(mech.run(Coroutine::park).named("First Child")); + co.fork(mech.run(Coroutine::park).named("Second Child")); + co.park(); + }) + .named("Group"); + + m_scheduler.schedule(group); + m_scheduler.run(); + + // second child interrupts first child + assertEquals( + List.of("Group", "Second Child"), + m_scheduler.getRunningCommands().stream().map(Command::name).toList()); + } + + @Test + void doesNotRunOnCancelWhenInterruptingOnDeck() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = mechanism.run(Coroutine::yield).named("Interrupter"); + m_scheduler.schedule(cmd); + m_scheduler.schedule(interrupter); + m_scheduler.run(); + + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void doesNotRunOnCancelWhenCancelingOnDeck() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + m_scheduler.schedule(cmd); + // canceling before calling .run() + m_scheduler.cancel(cmd); + m_scheduler.run(); + + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void runsOnCancelWhenInterruptingCommand() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd"); + var interrupter = mechanism.run(Coroutine::park).named("Interrupter"); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.schedule(interrupter); + m_scheduler.run(); + + assertTrue(ran.get(), "onCancel should have run!"); + } + + @Test + void doesNotRunOnCancelWhenCompleting() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.run(); + + assertFalse(m_scheduler.isScheduledOrRunning(cmd)); + assertFalse(ran.get(), "onCancel ran when it shouldn't have!"); + } + + @Test + void runsOnCancelWhenCanceling() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + m_scheduler.schedule(cmd); + m_scheduler.run(); + m_scheduler.cancel(cmd); + + assertTrue(ran.get(), "onCancel should have run!"); + } + + @Test + void runsOnCancelWhenCancelingParent() { + var ran = new AtomicBoolean(false); + + var mechanism = new Mechanism("The mechanism", m_scheduler); + var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd"); + + var group = new SequentialGroup("Seq", Collections.singletonList(cmd)); + m_scheduler.schedule(group); + m_scheduler.run(); + m_scheduler.cancel(group); + + assertTrue(ran.get(), "onCancel should have run!"); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java new file mode 100644 index 00000000000..15784af400e --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java @@ -0,0 +1,163 @@ +// 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 org.wpilib.commands3; + +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 static org.junit.jupiter.api.Assertions.assertTrue; + +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.function.Supplier; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Conflicts extends CommandTestBase { + @Test + void compositionsCannotAwaitConflictingCommands() { + var mech = new Mechanism("The Mechanism", m_scheduler); + + var group = + Command.noRequirements() + .executing( + co -> { + co.awaitAll( + mech.run(Coroutine::park).named("First"), + mech.run(Coroutine::park).named("Second")); + }) + .named("Group"); + + m_scheduler.schedule(group); + + // Running should attempt to schedule multiple conflicting commands + var exception = assertThrows(IllegalArgumentException.class, m_scheduler::run); + assertEquals( + "Commands running in parallel cannot share requirements: " + + "First and Second both require The Mechanism", + exception.getMessage()); + } + + @Test + void siblingsInCompositionCanShareRequirements() { + var mechanism = new Mechanism("The mechanism", m_scheduler); + var firstRan = new AtomicBoolean(false); + var secondRan = new AtomicBoolean(false); + + var first = + mechanism + .run( + c -> { + firstRan.set(true); + c.park(); + }) + .named("First"); + + var second = + mechanism + .run( + c -> { + secondRan.set(true); + c.park(); + }) + .named("Second"); + + var group = + Command.noRequirements() + .executing( + co -> { + co.fork(first); + co.fork(second); + co.park(); + }) + .named("Group"); + + m_scheduler.schedule(group); + m_scheduler.run(); + + assertTrue(firstRan.get(), "First child should have run to a yield point"); + assertTrue(secondRan.get(), "Second child should have run to a yield point"); + assertFalse( + m_scheduler.isScheduledOrRunning(first), "First child should have been interrupted"); + assertTrue(m_scheduler.isRunning(second), "Second child should still be running"); + assertTrue(m_scheduler.isRunning(group), "Group should still be running"); + } + + @Test + void nestedOneShotCompositionsAllRunInOneCycle() { + var runs = new AtomicInteger(0); + Supplier makeOneShot = + () -> Command.noRequirements().executing(_c -> runs.incrementAndGet()).named("One Shot"); + var command = + Command.noRequirements() + .executing( + co -> { + co.fork(makeOneShot.get()); + co.fork(makeOneShot.get()); + co.fork( + Command.noRequirements() + .executing(inner -> inner.fork(makeOneShot.get())) + .named("Inner")); + co.fork( + Command.noRequirements() + .executing( + co2 -> { + co2.fork(makeOneShot.get()); + co2.fork( + Command.noRequirements() + .executing( + co3 -> { + co3.fork(makeOneShot.get()); + }) + .named("3")); + }) + .named("2")); + }) + .named("Command"); + + m_scheduler.schedule(command); + m_scheduler.run(); + assertEquals(5, runs.get(), "All oneshot commands should have run"); + assertFalse(m_scheduler.isRunning(command), "Command should have exited after one cycle"); + } + + @Test + void childConflictsWithHigherPriorityTopLevel() { + var mechanism = new Mechanism("mechanism", m_scheduler); + var top = mechanism.run(Coroutine::park).withPriority(10).named("Top"); + + // Child conflicts with and is lower priority than the Top command + // It should not be scheduled, and the parent command should exit immediately + var child = mechanism.run(Coroutine::park).named("Child"); + var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent"); + + m_scheduler.schedule(top); + m_scheduler.schedule(parent); + m_scheduler.run(); + + assertTrue(m_scheduler.isRunning(top), "Top command should not have been interrupted"); + assertFalse(m_scheduler.isRunning(child), "Conflicting child should not have run"); + assertFalse(m_scheduler.isRunning(parent), "Parent of conflicting child should have exited"); + } + + @Test + void childConflictsWithLowerPriorityTopLevel() { + var mechanism = new Mechanism("mechanism", m_scheduler); + var top = mechanism.run(Coroutine::park).withPriority(-10).named("Top"); + + // Child conflicts with and is lower priority than the Top command + // It should not be scheduled, and the parent command should exit immediately + var child = mechanism.run(Coroutine::park).named("Child"); + var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent"); + + m_scheduler.schedule(top); + m_scheduler.schedule(parent); + m_scheduler.run(); + + assertFalse(m_scheduler.isRunning(top), "Top command should have been interrupted"); + assertTrue(m_scheduler.isRunning(child), "Conflicting child should be running"); + assertTrue(m_scheduler.isRunning(parent), "Parent of conflicting child should be running"); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java new file mode 100644 index 00000000000..bbc5c5d40ea --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java @@ -0,0 +1,224 @@ +// 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 org.wpilib.commands3; + +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 static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; + +import java.util.ArrayList; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Errors extends CommandTestBase { + @Test + @SuppressWarnings("PMD.AvoidCatchingGenericException") + void errorDetection() { + var mechanism = new Mechanism("X", m_scheduler); + + var command = + mechanism + .run( + coroutine -> { + throw new RuntimeException("The exception"); + }) + .named("Bad Behavior"); + + new Trigger(m_scheduler, () -> true).onTrue(command); + + try { + m_scheduler.run(); + fail("An exception should have been thrown"); + } catch (RuntimeException e) { + assertEquals("The exception", e.getMessage()); + + assertEquals( + "org.wpilib.commands3.SchedulerTest_Errors", e.getStackTrace()[0].getClassName()); + assertEquals("lambda$errorDetection$0", e.getStackTrace()[0].getMethodName()); + + assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); + + assertEquals(getClass().getName(), e.getStackTrace()[3].getClassName()); + assertEquals("errorDetection", e.getStackTrace()[3].getMethodName()); + } catch (Throwable t) { + fail("Expected a RuntimeException to be thrown, but got " + t); + } + } + + @Test + void nestedErrorDetection() { + var command = + Command.noRequirements() + .executing( + co -> { + co.await( + Command.noRequirements() + .executing( + c2 -> { + new Trigger(m_scheduler, () -> true) + .onTrue( + Command.noRequirements() + .executing( + c3 -> { + // Throws IndexOutOfBoundsException + var obj = new ArrayList<>(0).get(-1); + System.out.println(obj); // not reached + }) + .named("Throws IndexOutOfBounds")); + c2.park(); + }) + .named("Schedules With Trigger")); + }) + .named("Schedules Directly"); + + m_scheduler.schedule(command); + + // The first run sets up the trigger, but does not fire + // The second run will fire the trigger and cause the inner command to run and throw + m_scheduler.run(); + + try { + m_scheduler.run(); + fail("Index OOB exception expected"); + } catch (IndexOutOfBoundsException e) { + StackTraceElement[] stackTrace = e.getStackTrace(); + + assertEquals("Index -1 out of bounds for length 0", e.getMessage()); + int nestedIndex = 0; + for (; nestedIndex < stackTrace.length; nestedIndex++) { + if (stackTrace[nestedIndex].getClassName().equals(getClass().getName())) { + break; + } + } + + // user code trace for the scheduler run invocation (to `scheduler.run()` in the try block) + assertEquals("lambda$nestedErrorDetection$3", stackTrace[nestedIndex].getMethodName()); + assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 1].getMethodName()); + + // user code trace for where the command was scheduled (the `.onTrue()` line) + assertEquals("=== Command Binding Trace ===", stackTrace[nestedIndex + 2].getClassName()); + assertEquals("lambda$nestedErrorDetection$4", stackTrace[nestedIndex + 3].getMethodName()); + assertEquals("lambda$nestedErrorDetection$5", stackTrace[nestedIndex + 4].getMethodName()); + assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 5].getMethodName()); + } catch (Throwable unexpected) { + fail("Expected an IndexOutOfBoundsException to have been thrown, but got" + unexpected); + } + } + + @Test + void commandEncounteringErrorCancelsChildren() { + var child = Command.noRequirements().executing(Coroutine::park).named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.fork(child); + throw new RuntimeException("The exception"); + }) + .named("Bad Behavior"); + + m_scheduler.schedule(command); + assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isScheduledOrRunning(command), + "Command should have been removed from the scheduler"); + assertFalse( + m_scheduler.isScheduledOrRunning(child), + "Child should have been removed from the scheduler"); + } + + @Test + void childCommandEncounteringErrorCancelsParent() { + var child = + Command.noRequirements() + .executing( + co -> { + throw new RuntimeException("The exception"); // note: bubbles up to the parent + }) + .named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.await(child); + co.park(); // pretend other things would happen after the child + }) + .named("Parent"); + + m_scheduler.schedule(command); + assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isRunning(command), + "Parent command should have been removed from the scheduler"); + assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); + } + + @Test + @SuppressWarnings("PMD.CompareObjectsWithEquals") + void childCommandEncounteringErrorAfterRemountCancelsParent() { + var child = + Command.noRequirements() + .executing( + co -> { + co.yield(); + throw new RuntimeException("The exception"); // does not bubble up to the parent + }) + .named("Child 1"); + var command = + Command.noRequirements() + .executing( + co -> { + co.await(child); + co.park(); // pretend other things would happen after the child + }) + .named("Parent"); + + m_scheduler.schedule(command); + + // first run schedules the child and adds it to the running set + m_scheduler.run(); + + // second run encounters the error in the child + final var error = assertThrows(RuntimeException.class, m_scheduler::run); + assertFalse( + m_scheduler.isRunning(command), + "Parent command should have been removed from the scheduler"); + assertFalse(m_scheduler.isRunning(child), "Child should have been removed from the scheduler"); + + // Full event history + assertEquals(9, m_events.size()); + assertTrue( + m_events.get(0) instanceof SchedulerEvent.Scheduled s && s.command() == command, + "First event should be parent scheduled"); + assertTrue( + m_events.get(1) instanceof SchedulerEvent.Mounted m && m.command() == command, + "Second event should be parent mounted"); + assertTrue( + m_events.get(2) instanceof SchedulerEvent.Scheduled s && s.command() == child, + "Third event should be child scheduled"); + assertTrue( + m_events.get(3) instanceof SchedulerEvent.Mounted m && m.command() == child, + "Fourth event should be child mounted"); + assertTrue( + m_events.get(4) instanceof SchedulerEvent.Yielded y && y.command() == child, + "Fifth event should be child yielded"); + assertTrue( + m_events.get(5) instanceof SchedulerEvent.Yielded y && y.command() == command, + "Sixth event should be parent yielded"); + assertTrue( + m_events.get(6) instanceof SchedulerEvent.Mounted m && m.command() == child, + "Seventh event should be child remounted"); + assertTrue( + m_events.get(7) instanceof SchedulerEvent.CompletedWithError c + && c.command() == child + && c.error() == error, + "Eighth event should be child completed with error"); + assertTrue( + m_events.get(8) instanceof SchedulerEvent.Canceled c && c.command() == command, + "Ninth event should be parent canceled"); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java new file mode 100644 index 00000000000..534ca1cdce5 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java @@ -0,0 +1,69 @@ +// 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 org.wpilib.commands3; + +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; + +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Priorities extends CommandTestBase { + @Test + void higherPriorityCancels() { + final var subsystem = new Mechanism("Subsystem", m_scheduler); + + final var lower = new PriorityCommand(-1000, subsystem); + final var higher = new PriorityCommand(+1000, subsystem); + + m_scheduler.schedule(lower); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(lower)); + + m_scheduler.schedule(higher); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(higher)); + assertFalse(m_scheduler.isRunning(lower)); + } + + @Test + void lowerPriorityDoesNotCancel() { + final var subsystem = new Mechanism("Subsystem", m_scheduler); + + final var lower = new PriorityCommand(-1000, subsystem); + final var higher = new PriorityCommand(+1000, subsystem); + + m_scheduler.schedule(higher); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(higher)); + + m_scheduler.schedule(lower); + m_scheduler.run(); + if (!m_scheduler.isRunning(higher)) { + fail("Higher priority command should still be running"); + } + if (m_scheduler.isRunning(lower)) { + fail("Lower priority command should not be running"); + } + } + + @Test + void samePriorityCancels() { + final var subsystem = new Mechanism("Subsystem", m_scheduler); + + final var first = new PriorityCommand(512, subsystem); + final var second = new PriorityCommand(512, subsystem); + + m_scheduler.schedule(first); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(first)); + + m_scheduler.schedule(second); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(second), "New command should be running"); + assertFalse(m_scheduler.isRunning(first), "Old command should be canceled"); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java new file mode 100644 index 00000000000..7fa5bf74bb5 --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java @@ -0,0 +1,101 @@ +// 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 org.wpilib.commands3; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertThrowsExactly; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Sideloads extends CommandTestBase { + @Test + void sideloadThrowingException() { + m_scheduler.sideload( + co -> { + throw new RuntimeException("Bang!"); + }); + + // An exception raised in a sideload function should bubble up + assertEquals( + "Bang!", assertThrowsExactly(RuntimeException.class, m_scheduler::run).getMessage()); + } + + @Test + void periodicSideload() { + AtomicInteger count = new AtomicInteger(0); + m_scheduler.addPeriodic(count::incrementAndGet); + assertEquals(0, count.get()); + + m_scheduler.run(); + assertEquals(1, count.get()); + + m_scheduler.run(); + assertEquals(2, count.get()); + } + + @Test + void sideloadSchedulingCommand() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + // one-shot sideload forks a command and immediately exits + m_scheduler.sideload(co -> co.fork(command)); + m_scheduler.run(); + assertTrue( + m_scheduler.isRunning(command), "command should have started and outlasted the sideload"); + } + + @Test + void childCommandEscapesViaSideload() { + var child = Command.noRequirements().executing(Coroutine::park).named("Child"); + var parent = + Command.noRequirements() + .executing( + parentCoroutine -> { + m_scheduler.sideload(sidelodCoroutine -> sidelodCoroutine.fork(child)); + }) + .named("Parent"); + + m_scheduler.schedule(parent); + m_scheduler.run(); + assertFalse(m_scheduler.isScheduledOrRunning(parent), "parent should have exited"); + assertFalse( + m_scheduler.isScheduledOrRunning(child), + "the sideload to schedule the child should not have run yet"); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(child), "child should have started running"); + } + + @Test + void sideloadCancelingCommand() { + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + m_scheduler.schedule(command); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command), "command should have started"); + + m_scheduler.sideload(co -> m_scheduler.cancel(command)); + assertTrue(m_scheduler.isRunning(command), "sideload should not have run yet"); + + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command), "sideload should have canceled the command"); + } + + @Test + void sideloadAffectsStateForTriggerInSameCycle() { + AtomicBoolean signal = new AtomicBoolean(false); + var trigger = new Trigger(m_scheduler, signal::get); + var command = Command.noRequirements().executing(Coroutine::park).named("Command"); + trigger.onTrue(command); + m_scheduler.sideload(co -> signal.set(true)); + + m_scheduler.run(); + assertTrue(signal.get(), "Sideload should have run and set the signal"); + assertTrue(m_scheduler.isRunning(command), "Command should have started"); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java new file mode 100644 index 00000000000..9f16e7c5bec --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java @@ -0,0 +1,115 @@ +// 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 org.wpilib.commands3; + +import static org.junit.jupiter.api.Assertions.assertEquals; + +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Telemetry extends CommandTestBase { + @Test + void protobuf() { + var mech = new Mechanism("The mechanism", m_scheduler); + var parkCommand = mech.run(Coroutine::park).named("Park"); + var c3Command = mech.run(co -> co.await(parkCommand)).named("C3"); + var c2Command = mech.run(co -> co.await(c3Command)).named("C2"); + var group = mech.run(co -> co.await(c2Command)).named("Group"); + + m_scheduler.schedule(group); + m_scheduler.run(); + + var scheduledCommand1 = Command.noRequirements().executing(Coroutine::park).named("Command 1"); + var scheduledCommand2 = Command.noRequirements().executing(Coroutine::park).named("Command 2"); + m_scheduler.schedule(scheduledCommand1); + m_scheduler.schedule(scheduledCommand2); + + var message = Scheduler.proto.createMessage(); + Scheduler.proto.pack(message, m_scheduler); + var messageJson = message.toString(); + assertEquals( + """ + { + "lastTimeMs": %s, + "queuedCommands": [{ + "priority": 0, + "id": %s, + "name": "Command 1" + }, { + "priority": 0, + "id": %s, + "name": "Command 2" + }], + "runningCommands": [{ + "lastTimeMs": %s, + "totalTimeMs": %s, + "priority": 0, + "id": %s, + "name": "Group", + "requirements": [{ + "name": "The mechanism" + }] + }, { + "lastTimeMs": %s, + "totalTimeMs": %s, + "priority": 0, + "id": %s, + "parentId": %s, + "name": "C2", + "requirements": [{ + "name": "The mechanism" + }] + }, { + "lastTimeMs": %s, + "totalTimeMs": %s, + "priority": 0, + "id": %s, + "parentId": %s, + "name": "C3", + "requirements": [{ + "name": "The mechanism" + }] + }, { + "lastTimeMs": %s, + "totalTimeMs": %s, + "priority": 0, + "id": %s, + "parentId": %s, + "name": "Park", + "requirements": [{ + "name": "The mechanism" + }] + }] + }""" + .formatted( + // Scheduler data + m_scheduler.lastRuntimeMs(), + + // On deck commands + m_scheduler.runId(scheduledCommand1), + m_scheduler.runId(scheduledCommand2), + + // Running commands + m_scheduler.lastCommandRuntimeMs(group), + m_scheduler.totalRuntimeMs(group), + m_scheduler.runId(group), // id + // top-level command, no parent ID + + m_scheduler.lastCommandRuntimeMs(c2Command), + m_scheduler.totalRuntimeMs(c2Command), + m_scheduler.runId(c2Command), // id + m_scheduler.runId(group), // parent + m_scheduler.lastCommandRuntimeMs(c3Command), + m_scheduler.totalRuntimeMs(c3Command), + m_scheduler.runId(c3Command), // id + m_scheduler.runId(c2Command), // parent + m_scheduler.lastCommandRuntimeMs(parkCommand), + m_scheduler.totalRuntimeMs(parkCommand), + m_scheduler.runId(parkCommand), // id + m_scheduler.runId(c3Command) // parent + ), + messageJson); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java new file mode 100644 index 00000000000..fdc0f3955cb --- /dev/null +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java @@ -0,0 +1,187 @@ +// 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 org.wpilib.commands3; + +import static edu.wpi.first.units.Units.Microseconds; +import static edu.wpi.first.units.Units.Milliseconds; +import static edu.wpi.first.units.Units.Seconds; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import edu.wpi.first.wpilibj.RobotController; +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicLong; +import java.util.concurrent.atomic.AtomicReference; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("checkstyle:TypeName") +class SchedulerTest_Timing extends CommandTestBase { + @Test + void commandAwaitingItself() { + // This command deadlocks on itself. It's calling yield() in an infinite loop, which is + // equivalent to calling Coroutine.park(). No deleterious side effects other than stalling + // the command + AtomicReference commandRef = new AtomicReference<>(); + var command = + Command.noRequirements().executing(co -> co.await(commandRef.get())).named("Self Await"); + commandRef.set(command); + + m_scheduler.schedule(command); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command)); + } + + @Test + void commandDeadlock() { + AtomicReference ref1 = new AtomicReference<>(); + AtomicReference ref2 = new AtomicReference<>(); + + // Deadlock scenario: + // command1 starts, schedules command2, then waits for command2 to exit + // command2 starts, waits for command1 to exit + // + // Each successive run sees command1 mount, check for command2, then yield. + // Then sees command2 mount, check for command1, then also yield. + // This is like two threads spinwaiting for the other to exit. + // + // Externally canceling command2 allows command1 to continue + // Externally canceling command1 cancels both + var command1 = + Command.noRequirements().executing(co -> co.await(ref2.get())).named("Command 1"); + var command2 = + Command.noRequirements().executing(co -> co.await(ref1.get())).named("Command 2"); + ref1.set(command1); + ref2.set(command2); + + m_scheduler.schedule(command1); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command1)); + assertTrue(m_scheduler.isRunning(command2)); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(command1)); + assertTrue(m_scheduler.isRunning(command2)); + + m_scheduler.cancel(command1); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(command1)); + assertFalse(m_scheduler.isRunning(command2)); + } + + @Test + void forkedChildRunsOnce() { + AtomicInteger runCount = new AtomicInteger(0); + + var inner = + Command.noRequirements() + .executing( + co -> { + runCount.incrementAndGet(); + co.yield(); + + runCount.incrementAndGet(); + co.yield(); + }) + .named("Inner"); + + var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); + m_scheduler.schedule(outer); + m_scheduler.run(); + + assertEquals(1, runCount.get()); + } + + @Test + void shortWaitWaitsOneLoop() { + AtomicLong time = new AtomicLong(0); + RobotController.setTimeSource(time::get); + + AtomicBoolean completedWait = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing( + co -> { + co.wait(Milliseconds.of(1)); + completedWait.set(true); + }) + .named("Short Wait"); + + m_scheduler.schedule(command); + m_scheduler.run(); + + // wait 1 full second (much longer than the wait period) + time.set((long) Seconds.of(1).in(Microseconds)); + m_scheduler.run(); + assertTrue( + completedWait.get(), + "Command with a short wait should have completed if its duration has elapsed between runs"); + } + + @Test + void shortWaitWaitsOneLoopWithFastPeriod() { + AtomicLong time = new AtomicLong(0); + RobotController.setTimeSource(time::get); + AtomicBoolean completedWait = new AtomicBoolean(false); + var command = + Command.noRequirements() + .executing( + co -> { + co.wait(Milliseconds.of(1)); + completedWait.set(true); + }) + .named("Short Wait"); + + m_scheduler.schedule(command); + m_scheduler.run(); + + // move forward by half the wait period + time.set((long) Milliseconds.of(0.5).in(Microseconds)); + m_scheduler.run(); + assertFalse(completedWait.get(), "Command should still be waiting for 1 ms to elapse"); + + // move forward by the rest of the wait period + time.set((long) Milliseconds.of(1).in(Microseconds)); + m_scheduler.run(); + assertTrue( + completedWait.get(), + "Command with a short wait should have completed if its duration has elapsed between runs"); + } + + @Test + void awaitingExitsImmediatelyWithoutAOneLoopDelay() { + AtomicInteger innerRuns = new AtomicInteger(0); + var inner = + Command.noRequirements() + .executing( + co -> { + // executed immediately when forked + innerRuns.incrementAndGet(); + co.yield(); + + // executed again on the next scheduler run, after the forking command runs + innerRuns.incrementAndGet(); + }) + .named("Inner"); + + var outer = Command.noRequirements().executing(co -> co.await(inner)).named("Outer"); + m_scheduler.schedule(outer); + + // First run: runs outer, forks inner, inner runs to its first yield, outer yields + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(inner)); + assertTrue(m_scheduler.isRunning(outer)); + assertEquals(1, innerRuns.get()); + + // Second run: runs inner to completion, runs outer, outer sees inner is complete and exits + // NOTE: If child commands ran AFTER their parents, then outer would not have exited here and + // would take another scheduler run to complete + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(inner)); + assertFalse(m_scheduler.isRunning(outer)); + assertEquals(2, innerRuns.get()); + } +} diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java index b821de833b9..6bfa82c31c0 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java @@ -8,17 +8,9 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import java.util.List; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -class SequentialGroupTest { - private Scheduler m_scheduler; - - @BeforeEach - void setup() { - m_scheduler = new Scheduler(); - } - +class SequentialGroupTest extends CommandTestBase { @Test void single() { var command = Command.noRequirements().executing(Coroutine::yield).named("The Command"); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java index 6364729903a..fdc5b5dce5a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/TriggerTest.java @@ -8,21 +8,11 @@ import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; -import edu.wpi.first.wpilibj.RobotController; import java.util.List; import java.util.concurrent.atomic.AtomicBoolean; -import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -class TriggerTest { - private Scheduler m_scheduler; - - @BeforeEach - void setup() { - m_scheduler = new Scheduler(); - RobotController.setTimeSource(() -> System.nanoTime() / 1000); - } - +class TriggerTest extends CommandTestBase { @Test void onTrue() { var signal = new AtomicBoolean(false); diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index aeffebff229..b0fb7f01b2b 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -217,16 +217,6 @@ - - - - - - - - - - From 62fdc44a300cc05e009b9d2a5a7c026c9d812cdd Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 4 Sep 2025 18:58:17 -0400 Subject: [PATCH 127/153] Rename `SequenceBuilder` to `SequentialGroupBuilder` for consistency --- .../java/org/wpilib/commands3/Command.java | 10 +++++----- ...ilder.java => SequentialGroupBuilder.java} | 19 ++++++++++--------- 2 files changed, 15 insertions(+), 14 deletions(-) rename commandsv3/src/main/java/org/wpilib/commands3/{SequenceBuilder.java => SequentialGroupBuilder.java} (82%) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 55cc414e975..11c187c4238 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -295,14 +295,14 @@ static ParallelGroupBuilder race(Command... commands) { * run in the order they're passed to this method. * *

    More configuration options are needed after calling this function before the command can be - * created. See {@link SequenceBuilder} for details. + * created. See {@link SequentialGroupBuilder} for details. * * @param commands The commands to run in sequence. * @return A command builder */ - static SequenceBuilder sequence(Command... commands) { + static SequentialGroupBuilder sequence(Command... commands) { // parameters will be null checked by the builder - return new SequenceBuilder().andThen(commands); + return new SequentialGroupBuilder().andThen(commands); } /** @@ -366,9 +366,9 @@ default ParallelGroupBuilder until(BooleanSupplier endCondition) { * @param next The command to run after this one in the sequence * @return A sequence builder */ - default SequenceBuilder andThen(Command next) { + default SequentialGroupBuilder andThen(Command next) { // parameter will be null checked by the builder - return new SequenceBuilder().andThen(this).andThen(next); + return new SequentialGroupBuilder().andThen(this).andThen(next); } /** diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java similarity index 82% rename from commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java rename to commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java index 4d54bf9f65b..28048e10318 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequenceBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java @@ -18,15 +18,15 @@ * #named(String)} method, or with an automatically generated name using {@link * #withAutomaticName()}. */ -public class SequenceBuilder { +public class SequentialGroupBuilder { private final List m_steps = new ArrayList<>(); private BooleanSupplier m_endCondition; /** - * Creates new SequenceBuilder. The builder will have no commands and have no preapplied + * Creates new SequentialGroupBuilder. The builder will have no commands and have no preapplied * configuration options. Use {@link #andThen(Command)} to add commands to the sequence. */ - public SequenceBuilder() {} + public SequentialGroupBuilder() {} /** * Adds a command to the sequence. @@ -34,8 +34,8 @@ public SequenceBuilder() {} * @param next The next command in the sequence * @return The builder object, for chaining */ - public SequenceBuilder andThen(Command next) { - requireNonNullParam(next, "next", "SequenceBuilder.andThen"); + public SequentialGroupBuilder andThen(Command next) { + requireNonNullParam(next, "next", "SequentialGroupBuilder.andThen"); m_steps.add(next); return this; @@ -48,10 +48,11 @@ public SequenceBuilder andThen(Command next) { * @param nextCommands The next commands in the sequence * @return The builder object, for chaining */ - public SequenceBuilder andThen(Command... nextCommands) { - requireNonNullParam(nextCommands, "nextCommands", "SequenceBuilder.andThen"); + public SequentialGroupBuilder andThen(Command... nextCommands) { + requireNonNullParam(nextCommands, "nextCommands", "SequentialGroupBuilder.andThen"); for (int i = 0; i < nextCommands.length; i++) { - requireNonNullParam(nextCommands[i], "nextCommands[" + i + "]", "SequenceBuilder.andThen"); + requireNonNullParam( + nextCommands[i], "nextCommands[" + i + "]", "SequentialGroupBuilder.andThen"); } m_steps.addAll(Arrays.asList(nextCommands)); @@ -67,7 +68,7 @@ public SequenceBuilder andThen(Command... nextCommands) { * @param endCondition The end condition for the group * @return The builder object, for chaining */ - public SequenceBuilder until(BooleanSupplier endCondition) { + public SequentialGroupBuilder until(BooleanSupplier endCondition) { m_endCondition = endCondition; return this; } From eebbc59d15a19b8d2377228416ab5a2e0100a291 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 11:02:49 -0400 Subject: [PATCH 128/153] Protobuf reorganization Move to a single generated file, instead of one file per class Rename top-level file so it doesn't conflict with the main scheduler class in IDE autocompletion (is now "ProtobufCommands" instead of "Scheduler") Use packArray for nested array components instead of a manual loop Clear message objects before use to ensure optional fields are blank if a message buffer is reused for different objects --- .../commands3/proto/ProtobufCommand.java | 996 --------- .../commands3/proto/ProtobufCommands.java | 1879 +++++++++++++++++ .../commands3/proto/ProtobufMechanism.java | 299 --- .../commands3/proto/ProtobufScheduler.java | 562 ----- .../org/wpilib/commands3/proto/Scheduler.java | 70 - .../wpilib/commands3/proto/CommandProto.java | 14 +- .../commands3/proto/MechanismProto.java | 2 + .../commands3/proto/SchedulerProto.java | 28 +- ...cheduler.proto => protobuf_commands.proto} | 3 +- .../commands3/SchedulerTest_Telemetry.java | 6 +- 10 files changed, 1909 insertions(+), 1950 deletions(-) delete mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java create mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java delete mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java delete mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java delete mode 100644 commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java rename commandsv3/src/main/proto/{scheduler.proto => protobuf_commands.proto} (94%) diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java deleted file mode 100644 index 50b626e1f27..00000000000 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommand.java +++ /dev/null @@ -1,996 +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. -// Code generated by protocol buffer compiler. Do not edit! -package org.wpilib.commands3.proto; - -import java.io.IOException; -import us.hebi.quickbuf.Descriptors; -import us.hebi.quickbuf.FieldName; -import us.hebi.quickbuf.InvalidProtocolBufferException; -import us.hebi.quickbuf.JsonSink; -import us.hebi.quickbuf.JsonSource; -import us.hebi.quickbuf.MessageFactory; -import us.hebi.quickbuf.ProtoMessage; -import us.hebi.quickbuf.ProtoSink; -import us.hebi.quickbuf.ProtoSource; -import us.hebi.quickbuf.ProtoUtil; -import us.hebi.quickbuf.RepeatedMessage; -import us.hebi.quickbuf.Utf8String; - -/** - * Protobuf type {@code ProtobufCommand} - */ -@SuppressWarnings("hiding") -public final class ProtobufCommand extends ProtoMessage implements Cloneable { - private static final long serialVersionUID = 0L; - - /** - *

    -   *  How much time the command took to execute in its most recent run.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double last_time_ms = 6; - */ - private double lastTimeMs; - - /** - *
    -   *  How long the command has taken to run, in aggregate.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double total_time_ms = 7; - */ - private double totalTimeMs; - - /** - *
    -   *  The priority level of the command.
    -   * 
    - * - * optional int32 priority = 4; - */ - private int priority; - - /** - *
    -   *  A unique ID for the command.
    -   *  Different invocations of the same command object have different IDs.
    -   * 
    - * - * optional uint32 id = 1; - */ - private int id; - - /** - *
    -   *  The ID of the parent command.
    -   *  Not included in the message for top-level commands.
    -   * 
    - * - * optional uint32 parent_id = 2; - */ - private int parentId; - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - */ - private final Utf8String name = Utf8String.newEmptyInstance(); - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - */ - private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufMechanism.getFactory()); - - private ProtobufCommand() { - } - - /** - * @return a new empty instance of {@code ProtobufCommand} - */ - public static ProtobufCommand newInstance() { - return new ProtobufCommand(); - } - - /** - *
    -   *  How much time the command took to execute in its most recent run.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double last_time_ms = 6; - * @return whether the lastTimeMs field is set - */ - public boolean hasLastTimeMs() { - return (bitField0_ & 0x00000002) != 0; - } - - /** - *
    -   *  How much time the command took to execute in its most recent run.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double last_time_ms = 6; - * @return this - */ - public ProtobufCommand clearLastTimeMs() { - bitField0_ &= ~0x00000002; - lastTimeMs = 0D; - return this; - } - - /** - *
    -   *  How much time the command took to execute in its most recent run.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double last_time_ms = 6; - * @return the lastTimeMs - */ - public double getLastTimeMs() { - return lastTimeMs; - } - - /** - *
    -   *  How much time the command took to execute in its most recent run.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double last_time_ms = 6; - * @param value the lastTimeMs to set - * @return this - */ - public ProtobufCommand setLastTimeMs(final double value) { - bitField0_ |= 0x00000002; - lastTimeMs = value; - return this; - } - - /** - *
    -   *  How long the command has taken to run, in aggregate.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double total_time_ms = 7; - * @return whether the totalTimeMs field is set - */ - public boolean hasTotalTimeMs() { - return (bitField0_ & 0x00000001) != 0; - } - - /** - *
    -   *  How long the command has taken to run, in aggregate.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double total_time_ms = 7; - * @return this - */ - public ProtobufCommand clearTotalTimeMs() { - bitField0_ &= ~0x00000001; - totalTimeMs = 0D; - return this; - } - - /** - *
    -   *  How long the command has taken to run, in aggregate.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double total_time_ms = 7; - * @return the totalTimeMs - */ - public double getTotalTimeMs() { - return totalTimeMs; - } - - /** - *
    -   *  How long the command has taken to run, in aggregate.
    -   *  Only included in a message for an actively running command.
    -   * 
    - * - * optional double total_time_ms = 7; - * @param value the totalTimeMs to set - * @return this - */ - public ProtobufCommand setTotalTimeMs(final double value) { - bitField0_ |= 0x00000001; - totalTimeMs = value; - return this; - } - - /** - *
    -   *  The priority level of the command.
    -   * 
    - * - * optional int32 priority = 4; - * @return whether the priority field is set - */ - public boolean hasPriority() { - return (bitField0_ & 0x00000008) != 0; - } - - /** - *
    -   *  The priority level of the command.
    -   * 
    - * - * optional int32 priority = 4; - * @return this - */ - public ProtobufCommand clearPriority() { - bitField0_ &= ~0x00000008; - priority = 0; - return this; - } - - /** - *
    -   *  The priority level of the command.
    -   * 
    - * - * optional int32 priority = 4; - * @return the priority - */ - public int getPriority() { - return priority; - } - - /** - *
    -   *  The priority level of the command.
    -   * 
    - * - * optional int32 priority = 4; - * @param value the priority to set - * @return this - */ - public ProtobufCommand setPriority(final int value) { - bitField0_ |= 0x00000008; - priority = value; - return this; - } - - /** - *
    -   *  A unique ID for the command.
    -   *  Different invocations of the same command object have different IDs.
    -   * 
    - * - * optional uint32 id = 1; - * @return whether the id field is set - */ - public boolean hasId() { - return (bitField0_ & 0x00000010) != 0; - } - - /** - *
    -   *  A unique ID for the command.
    -   *  Different invocations of the same command object have different IDs.
    -   * 
    - * - * optional uint32 id = 1; - * @return this - */ - public ProtobufCommand clearId() { - bitField0_ &= ~0x00000010; - id = 0; - return this; - } - - /** - *
    -   *  A unique ID for the command.
    -   *  Different invocations of the same command object have different IDs.
    -   * 
    - * - * optional uint32 id = 1; - * @return the id - */ - public int getId() { - return id; - } - - /** - *
    -   *  A unique ID for the command.
    -   *  Different invocations of the same command object have different IDs.
    -   * 
    - * - * optional uint32 id = 1; - * @param value the id to set - * @return this - */ - public ProtobufCommand setId(final int value) { - bitField0_ |= 0x00000010; - id = value; - return this; - } - - /** - *
    -   *  The ID of the parent command.
    -   *  Not included in the message for top-level commands.
    -   * 
    - * - * optional uint32 parent_id = 2; - * @return whether the parentId field is set - */ - public boolean hasParentId() { - return (bitField0_ & 0x00000004) != 0; - } - - /** - *
    -   *  The ID of the parent command.
    -   *  Not included in the message for top-level commands.
    -   * 
    - * - * optional uint32 parent_id = 2; - * @return this - */ - public ProtobufCommand clearParentId() { - bitField0_ &= ~0x00000004; - parentId = 0; - return this; - } - - /** - *
    -   *  The ID of the parent command.
    -   *  Not included in the message for top-level commands.
    -   * 
    - * - * optional uint32 parent_id = 2; - * @return the parentId - */ - public int getParentId() { - return parentId; - } - - /** - *
    -   *  The ID of the parent command.
    -   *  Not included in the message for top-level commands.
    -   * 
    - * - * optional uint32 parent_id = 2; - * @param value the parentId to set - * @return this - */ - public ProtobufCommand setParentId(final int value) { - bitField0_ |= 0x00000004; - parentId = value; - return this; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @return whether the name field is set - */ - public boolean hasName() { - return (bitField0_ & 0x00000020) != 0; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @return this - */ - public ProtobufCommand clearName() { - bitField0_ &= ~0x00000020; - name.clear(); - return this; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @return the name - */ - public String getName() { - return name.getString(); - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @return internal {@code Utf8String} representation of name for reading - */ - public Utf8String getNameBytes() { - return this.name; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @return internal {@code Utf8String} representation of name for modifications - */ - public Utf8String getMutableNameBytes() { - bitField0_ |= 0x00000020; - return this.name; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @param value the name to set - * @return this - */ - public ProtobufCommand setName(final CharSequence value) { - bitField0_ |= 0x00000020; - name.copyFrom(value); - return this; - } - - /** - *
    -   *  The name of the command.
    -   * 
    - * - * optional string name = 3; - * @param value the name to set - * @return this - */ - public ProtobufCommand setName(final Utf8String value) { - bitField0_ |= 0x00000020; - name.copyFrom(value); - return this; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * @return whether the requirements field is set - */ - public boolean hasRequirements() { - return (bitField0_ & 0x00000040) != 0; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * @return this - */ - public ProtobufCommand clearRequirements() { - bitField0_ &= ~0x00000040; - requirements.clear(); - return this; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * - * This method returns the internal storage object without modifying any has state. - * The returned object should not be modified and be treated as read-only. - * - * Use {@link #getMutableRequirements()} if you want to modify it. - * - * @return internal storage object for reading - */ - public RepeatedMessage getRequirements() { - return requirements; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * - * This method returns the internal storage object and sets the corresponding - * has state. The returned object will become part of this message and its - * contents may be modified as long as the has state is not cleared. - * - * @return internal storage object for modifications - */ - public RepeatedMessage getMutableRequirements() { - bitField0_ |= 0x00000040; - return requirements; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * @param value the requirements to add - * @return this - */ - public ProtobufCommand addRequirements(final ProtobufMechanism value) { - bitField0_ |= 0x00000040; - requirements.add(value); - return this; - } - - /** - *
    -   *  The mechanisms required by the command.
    -   * 
    - * - * repeated .wpi.proto.ProtobufMechanism requirements = 5; - * @param values the requirements to add - * @return this - */ - public ProtobufCommand addAllRequirements(final ProtobufMechanism... values) { - bitField0_ |= 0x00000040; - requirements.addAll(values); - return this; - } - - @Override - public ProtobufCommand copyFrom(final ProtobufCommand other) { - cachedSize = other.cachedSize; - if ((bitField0_ | other.bitField0_) != 0) { - bitField0_ = other.bitField0_; - lastTimeMs = other.lastTimeMs; - totalTimeMs = other.totalTimeMs; - priority = other.priority; - id = other.id; - parentId = other.parentId; - name.copyFrom(other.name); - requirements.copyFrom(other.requirements); - } - return this; - } - - @Override - public ProtobufCommand mergeFrom(final ProtobufCommand other) { - if (other.isEmpty()) { - return this; - } - cachedSize = -1; - if (other.hasLastTimeMs()) { - setLastTimeMs(other.lastTimeMs); - } - if (other.hasTotalTimeMs()) { - setTotalTimeMs(other.totalTimeMs); - } - if (other.hasPriority()) { - setPriority(other.priority); - } - if (other.hasId()) { - setId(other.id); - } - if (other.hasParentId()) { - setParentId(other.parentId); - } - if (other.hasName()) { - getMutableNameBytes().copyFrom(other.name); - } - if (other.hasRequirements()) { - getMutableRequirements().addAll(other.requirements); - } - return this; - } - - @Override - public ProtobufCommand clear() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - lastTimeMs = 0D; - totalTimeMs = 0D; - priority = 0; - id = 0; - parentId = 0; - name.clear(); - requirements.clear(); - return this; - } - - @Override - public ProtobufCommand clearQuick() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - name.clear(); - requirements.clearQuick(); - return this; - } - - @Override - public boolean equals(Object o) { - if (o == this) { - return true; - } - if (!(o instanceof ProtobufCommand)) { - return false; - } - ProtobufCommand other = (ProtobufCommand) o; - return bitField0_ == other.bitField0_ - && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) - && (!hasTotalTimeMs() || ProtoUtil.isEqual(totalTimeMs, other.totalTimeMs)) - && (!hasPriority() || priority == other.priority) - && (!hasId() || id == other.id) - && (!hasParentId() || parentId == other.parentId) - && (!hasName() || name.equals(other.name)) - && (!hasRequirements() || requirements.equals(other.requirements)); - } - - @Override - public void writeTo(final ProtoSink output) throws IOException { - if ((bitField0_ & 0x00000002) != 0) { - output.writeRawByte((byte) 49); - output.writeDoubleNoTag(lastTimeMs); - } - if ((bitField0_ & 0x00000001) != 0) { - output.writeRawByte((byte) 57); - output.writeDoubleNoTag(totalTimeMs); - } - if ((bitField0_ & 0x00000008) != 0) { - output.writeRawByte((byte) 32); - output.writeInt32NoTag(priority); - } - if ((bitField0_ & 0x00000010) != 0) { - output.writeRawByte((byte) 8); - output.writeUInt32NoTag(id); - } - if ((bitField0_ & 0x00000004) != 0) { - output.writeRawByte((byte) 16); - output.writeUInt32NoTag(parentId); - } - if ((bitField0_ & 0x00000020) != 0) { - output.writeRawByte((byte) 26); - output.writeStringNoTag(name); - } - if ((bitField0_ & 0x00000040) != 0) { - for (int i = 0; i < requirements.length(); i++) { - output.writeRawByte((byte) 42); - output.writeMessageNoTag(requirements.get(i)); - } - } - } - - @Override - protected int computeSerializedSize() { - int size = 0; - if ((bitField0_ & 0x00000002) != 0) { - size += 9; - } - if ((bitField0_ & 0x00000001) != 0) { - size += 9; - } - if ((bitField0_ & 0x00000008) != 0) { - size += 1 + ProtoSink.computeInt32SizeNoTag(priority); - } - if ((bitField0_ & 0x00000010) != 0) { - size += 1 + ProtoSink.computeUInt32SizeNoTag(id); - } - if ((bitField0_ & 0x00000004) != 0) { - size += 1 + ProtoSink.computeUInt32SizeNoTag(parentId); - } - if ((bitField0_ & 0x00000020) != 0) { - size += 1 + ProtoSink.computeStringSizeNoTag(name); - } - if ((bitField0_ & 0x00000040) != 0) { - size += (1 * requirements.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(requirements); - } - return size; - } - - @Override - @SuppressWarnings("fallthrough") - public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { - // Enabled Fall-Through Optimization (QuickBuffers) - int tag = input.readTag(); - while (true) { - switch (tag) { - case 49: { - // lastTimeMs - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000002; - tag = input.readTag(); - if (tag != 57) { - break; - } - } - case 57: { - // totalTimeMs - totalTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 32) { - break; - } - } - case 32: { - // priority - priority = input.readInt32(); - bitField0_ |= 0x00000008; - tag = input.readTag(); - if (tag != 8) { - break; - } - } - case 8: { - // id - id = input.readUInt32(); - bitField0_ |= 0x00000010; - tag = input.readTag(); - if (tag != 16) { - break; - } - } - case 16: { - // parentId - parentId = input.readUInt32(); - bitField0_ |= 0x00000004; - tag = input.readTag(); - if (tag != 26) { - break; - } - } - case 26: { - // name - input.readString(name); - bitField0_ |= 0x00000020; - tag = input.readTag(); - if (tag != 42) { - break; - } - } - case 42: { - // requirements - tag = input.readRepeatedMessage(requirements, tag); - bitField0_ |= 0x00000040; - if (tag != 0) { - break; - } - } - case 0: { - return this; - } - default: { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } - } - } - } - - @Override - public void writeTo(final JsonSink output) throws IOException { - output.beginObject(); - if ((bitField0_ & 0x00000002) != 0) { - output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); - } - if ((bitField0_ & 0x00000001) != 0) { - output.writeDouble(FieldNames.totalTimeMs, totalTimeMs); - } - if ((bitField0_ & 0x00000008) != 0) { - output.writeInt32(FieldNames.priority, priority); - } - if ((bitField0_ & 0x00000010) != 0) { - output.writeUInt32(FieldNames.id, id); - } - if ((bitField0_ & 0x00000004) != 0) { - output.writeUInt32(FieldNames.parentId, parentId); - } - if ((bitField0_ & 0x00000020) != 0) { - output.writeString(FieldNames.name, name); - } - if ((bitField0_ & 0x00000040) != 0) { - output.writeRepeatedMessage(FieldNames.requirements, requirements); - } - output.endObject(); - } - - @Override - public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { - if (!input.beginObject()) { - return this; - } - while (!input.isAtEnd()) { - switch (input.readFieldHash()) { - case 1958056841: - case -740797521: { - if (input.isAtField(FieldNames.lastTimeMs)) { - if (!input.trySkipNullValue()) { - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000002; - } - } else { - input.skipUnknownField(); - } - break; - } - case -717217353: - case 1006112349: { - if (input.isAtField(FieldNames.totalTimeMs)) { - if (!input.trySkipNullValue()) { - totalTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); - } - break; - } - case -1165461084: { - if (input.isAtField(FieldNames.priority)) { - if (!input.trySkipNullValue()) { - priority = input.readInt32(); - bitField0_ |= 0x00000008; - } - } else { - input.skipUnknownField(); - } - break; - } - case 3355: { - if (input.isAtField(FieldNames.id)) { - if (!input.trySkipNullValue()) { - id = input.readUInt32(); - bitField0_ |= 0x00000010; - } - } else { - input.skipUnknownField(); - } - break; - } - case 1175162725: - case 2070327504: { - if (input.isAtField(FieldNames.parentId)) { - if (!input.trySkipNullValue()) { - parentId = input.readUInt32(); - bitField0_ |= 0x00000004; - } - } else { - input.skipUnknownField(); - } - break; - } - case 3373707: { - if (input.isAtField(FieldNames.name)) { - if (!input.trySkipNullValue()) { - input.readString(name); - bitField0_ |= 0x00000020; - } - } else { - input.skipUnknownField(); - } - break; - } - case -1619874672: { - if (input.isAtField(FieldNames.requirements)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(requirements); - bitField0_ |= 0x00000040; - } - } else { - input.skipUnknownField(); - } - break; - } - default: { - input.skipUnknownField(); - break; - } - } - } - input.endObject(); - return this; - } - - @Override - public ProtobufCommand clone() { - return new ProtobufCommand().copyFrom(this); - } - - @Override - public boolean isEmpty() { - return ((bitField0_) == 0); - } - - public static ProtobufCommand parseFrom(final byte[] data) throws InvalidProtocolBufferException { - return ProtoMessage.mergeFrom(new ProtobufCommand(), data).checkInitialized(); - } - - public static ProtobufCommand parseFrom(final ProtoSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); - } - - public static ProtobufCommand parseFrom(final JsonSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); - } - - /** - * @return factory for creating ProtobufCommand messages - */ - public static MessageFactory getFactory() { - return ProtobufCommandFactory.INSTANCE; - } - - /** - * @return this type's descriptor. - */ - public static Descriptors.Descriptor getDescriptor() { - return Scheduler.wpi_proto_ProtobufCommand_descriptor; - } - - private enum ProtobufCommandFactory implements MessageFactory { - INSTANCE; - - @Override - public ProtobufCommand create() { - return ProtobufCommand.newInstance(); - } - } - - /** - * Contains name constants used for serializing JSON - */ - static class FieldNames { - static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); - - static final FieldName totalTimeMs = FieldName.forField("totalTimeMs", "total_time_ms"); - - static final FieldName priority = FieldName.forField("priority"); - - static final FieldName id = FieldName.forField("id"); - - static final FieldName parentId = FieldName.forField("parentId", "parent_id"); - - static final FieldName name = FieldName.forField("name"); - - static final FieldName requirements = FieldName.forField("requirements"); - } -} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java new file mode 100644 index 00000000000..e8b69923f02 --- /dev/null +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java @@ -0,0 +1,1879 @@ +// Code generated by protocol buffer compiler. Do not edit! +package org.wpilib.commands3.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; +import us.hebi.quickbuf.RepeatedMessage; +import us.hebi.quickbuf.Utf8String; + +public final class ProtobufCommands { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2495, + "CjFjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3Byb3RvYnVmX2NvbW1hbmRzLnByb3RvEgl3cGkucHJv" + + "dG8iJwoRUHJvdG9idWZNZWNoYW5pc20SEgoEbmFtZRgBIAEoCVIEbmFtZSK2AgoPUHJvdG9idWZDb21t" + + "YW5kEg4KAmlkGAEgASgNUgJpZBIgCglwYXJlbnRfaWQYAiABKA1IAFIIcGFyZW50SWSIAQESEgoEbmFt" + + "ZRgDIAEoCVIEbmFtZRIaCghwcmlvcml0eRgEIAEoBVIIcHJpb3JpdHkSQAoMcmVxdWlyZW1lbnRzGAUg" + + "AygLMhwud3BpLnByb3RvLlByb3RvYnVmTWVjaGFuaXNtUgxyZXF1aXJlbWVudHMSJQoMbGFzdF90aW1l" + + "X21zGAYgASgBSAFSCmxhc3RUaW1lTXOIAQESJwoNdG90YWxfdGltZV9tcxgHIAEoAUgCUgt0b3RhbFRp" + + "bWVNc4gBAUIMCgpfcGFyZW50X2lkQg8KDV9sYXN0X3RpbWVfbXNCEAoOX3RvdGFsX3RpbWVfbXMiwQEK" + + "EVByb3RvYnVmU2NoZWR1bGVyEkMKD3F1ZXVlZF9jb21tYW5kcxgBIAMoCzIaLndwaS5wcm90by5Qcm90" + + "b2J1ZkNvbW1hbmRSDnF1ZXVlZENvbW1hbmRzEkUKEHJ1bm5pbmdfY29tbWFuZHMYAiADKAsyGi53cGku" + + "cHJvdG8uUHJvdG9idWZDb21tYW5kUg9ydW5uaW5nQ29tbWFuZHMSIAoMbGFzdF90aW1lX21zGAMgASgB" + + "UgpsYXN0VGltZU1zQhwKGm9yZy53cGlsaWIuY29tbWFuZHMzLnByb3RvSrIOCgYSBAAANAEKCAoBDBID" + + "AAASCggKAQISAwIAEgoICgEIEgMEADMKCQoCCAESAwQAMwqnAQoCBAASBAwADgEymgEKYWxsd3BpbGli" + + "ICQgcHJvdG9jLXF1aWNrYnVmIFwKLS1xdWlja2J1Zl9vdXQ9Z2VuX2Rlc2NyaXB0b3JzPXRydWU6Y29t" + + "bWFuZHN2My9zcmMvZ2VuZXJhdGVkL21haW4vamF2YSBcCmNvbW1hbmRzdjMvc3JjL21haW4vcHJvdG8v" + + "cHJvdG9idWZfY29tbWFuZHMucHJvdG8KCgoKAwQAARIDDAgZCgsKBAQAAgASAw0CEgoMCgUEAAIABRID" + + "DQIICgwKBQQAAgABEgMNCQ0KDAoFBAACAAMSAw0QEQoKCgIEARIEEAApAQoKCgMEAQESAxAIFwpxCgQE" + + "AQIAEgMTAhAaZCBBIHVuaXF1ZSBJRCBmb3IgdGhlIGNvbW1hbmQuCiBEaWZmZXJlbnQgaW52b2NhdGlv" + + "bnMgb2YgdGhlIHNhbWUgY29tbWFuZCBvYmplY3QgaGF2ZSBkaWZmZXJlbnQgSURzLgoKDAoFBAECAAUS" + + "AxMCCAoMCgUEAQIAARIDEwkLCgwKBQQBAgADEgMTDg8KYQoEBAECARIDFwIgGlQgVGhlIElEIG9mIHRo" + + "ZSBwYXJlbnQgY29tbWFuZC4KIE5vdCBpbmNsdWRlZCBpbiB0aGUgbWVzc2FnZSBmb3IgdG9wLWxldmVs", + "IGNvbW1hbmRzLgoKDAoFBAECAQQSAxcCCgoMCgUEAQIBBRIDFwsRCgwKBQQBAgEBEgMXEhsKDAoFBAEC" + + "AQMSAxceHwonCgQEAQICEgMaAhIaGiBUaGUgbmFtZSBvZiB0aGUgY29tbWFuZC4KCgwKBQQBAgIFEgMa" + + "AggKDAoFBAECAgESAxoJDQoMCgUEAQICAxIDGhARCjEKBAQBAgMSAx0CFRokIFRoZSBwcmlvcml0eSBs" + + "ZXZlbCBvZiB0aGUgY29tbWFuZC4KCgwKBQQBAgMFEgMdAgcKDAoFBAECAwESAx0IEAoMCgUEAQIDAxID" + + "HRMUCjYKBAQBAgQSAyACLhopIFRoZSBtZWNoYW5pc21zIHJlcXVpcmVkIGJ5IHRoZSBjb21tYW5kLgoK" + + "DAoFBAECBAQSAyACCgoMCgUEAQIEBhIDIAscCgwKBQQBAgQBEgMgHSkKDAoFBAECBAMSAyAsLQqOAQoE" + + "BAECBRIDJAIjGoABIEhvdyBtdWNoIHRpbWUgdGhlIGNvbW1hbmQgdG9vayB0byBleGVjdXRlIGluIGl0" + + "cyBtb3N0IHJlY2VudCBydW4uCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZl" + + "bHkgcnVubmluZyBjb21tYW5kLgoKDAoFBAECBQQSAyQCCgoMCgUEAQIFBRIDJAsRCgwKBQQBAgUBEgMk" + + "Eh4KDAoFBAECBQMSAyQhIgqAAQoEBAECBhIDKAIkGnMgSG93IGxvbmcgdGhlIGNvbW1hbmQgaGFzIHRh" + + "a2VuIHRvIHJ1biwgaW4gYWdncmVnYXRlLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFu" + + "IGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgYEEgMoAgoKDAoFBAECBgUSAygLEQoMCgUE" + + "AQIGARIDKBIfCgwKBQQBAgYDEgMoIiMKCgoCBAISBCsANAEKCgoDBAIBEgMrCBkKjQIKBAQCAgASAy8C" + + "Lxr/ASBOb3RlOiBjb21tYW5kcyBhcmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2gg" + + "b2NjdXJzIGltbWVkaWF0ZWx5IGJlZm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5p" + + "bmcuIEVudHJpZXMgd2lsbCBvbmx5IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVs" + + "ZXIKIF9hZnRlcl8gbWFudWFsbHkgc2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxp" + + "bmcgc2NoZWR1bGVyLnJ1bigpCgoMCgUEAgIABBIDLwIKCgwKBQQCAgAGEgMvCxoKDAoFBAICAAESAy8b" + + "KgoMCgUEAgIAAxIDLy0uCgsKBAQCAgESAzACMAoMCgUEAgIBBBIDMAIKCgwKBQQCAgEGEgMwCxoKDAoF" + + "BAICAQESAzAbKwoMCgUEAgIBAxIDMC4vCk8KBAQCAgISAzMCGhpCIEhvdyBtdWNoIHRpbWUgdGhlIHNj", + "aGVkdWxlciB0b29rIGluIGl0cyBsYXN0IGBydW4oKWAgaW52b2NhdGlvbi4KCgwKBQQCAgIFEgMzAggK" + + "DAoFBAICAgESAzMJFQoMCgUEAgICAxIDMxgZYgZwcm90bzM="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("commandsv3/src/main/proto/protobuf_commands.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufMechanism_descriptor = descriptor.internalContainedType(64, 39, "ProtobufMechanism", "wpi.proto.ProtobufMechanism"); + + static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(106, 310, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + + static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(419, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufMechanism} + */ + public static final class ProtobufMechanism extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional string name = 1; + */ + private final Utf8String name = Utf8String.newEmptyInstance(); + + private ProtobufMechanism() { + } + + /** + * @return a new empty instance of {@code ProtobufMechanism} + */ + public static ProtobufMechanism newInstance() { + return new ProtobufMechanism(); + } + + /** + * optional string name = 1; + * @return whether the name field is set + */ + public boolean hasName() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional string name = 1; + * @return this + */ + public ProtobufMechanism clearName() { + bitField0_ &= ~0x00000001; + name.clear(); + return this; + } + + /** + * optional string name = 1; + * @return the name + */ + public String getName() { + return name.getString(); + } + + /** + * optional string name = 1; + * @return internal {@code Utf8String} representation of name for reading + */ + public Utf8String getNameBytes() { + return this.name; + } + + /** + * optional string name = 1; + * @return internal {@code Utf8String} representation of name for modifications + */ + public Utf8String getMutableNameBytes() { + bitField0_ |= 0x00000001; + return this.name; + } + + /** + * optional string name = 1; + * @param value the name to set + * @return this + */ + public ProtobufMechanism setName(final CharSequence value) { + bitField0_ |= 0x00000001; + name.copyFrom(value); + return this; + } + + /** + * optional string name = 1; + * @param value the name to set + * @return this + */ + public ProtobufMechanism setName(final Utf8String value) { + bitField0_ |= 0x00000001; + name.copyFrom(value); + return this; + } + + @Override + public ProtobufMechanism copyFrom(final ProtobufMechanism other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + name.copyFrom(other.name); + } + return this; + } + + @Override + public ProtobufMechanism mergeFrom(final ProtobufMechanism other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasName()) { + getMutableNameBytes().copyFrom(other.name); + } + return this; + } + + @Override + public ProtobufMechanism clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + return this; + } + + @Override + public ProtobufMechanism clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMechanism)) { + return false; + } + ProtobufMechanism other = (ProtobufMechanism) o; + return bitField0_ == other.bitField0_ + && (!hasName() || name.equals(other.name)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeStringNoTag(name); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeStringSizeNoTag(name); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMechanism mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // name + input.readString(name); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeString(FieldNames.name, name); + } + output.endObject(); + } + + @Override + public ProtobufMechanism mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3373707: { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMechanism clone() { + return new ProtobufMechanism().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMechanism parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMechanism(), data).checkInitialized(); + } + + public static ProtobufMechanism parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); + } + + public static ProtobufMechanism parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMechanism messages + */ + public static MessageFactory getFactory() { + return ProtobufMechanismFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return ProtobufCommands.wpi_proto_ProtobufMechanism_descriptor; + } + + private enum ProtobufMechanismFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMechanism create() { + return ProtobufMechanism.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName name = FieldName.forField("name"); + } + } + + /** + * Protobuf type {@code ProtobufCommand} + */ + public static final class ProtobufCommand extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + *
    +     *  How much time the command took to execute in its most recent run.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double last_time_ms = 6; + */ + private double lastTimeMs; + + /** + *
    +     *  How long the command has taken to run, in aggregate.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double total_time_ms = 7; + */ + private double totalTimeMs; + + /** + *
    +     *  The priority level of the command.
    +     * 
    + * + * optional int32 priority = 4; + */ + private int priority; + + /** + *
    +     *  A unique ID for the command.
    +     *  Different invocations of the same command object have different IDs.
    +     * 
    + * + * optional uint32 id = 1; + */ + private int id; + + /** + *
    +     *  The ID of the parent command.
    +     *  Not included in the message for top-level commands.
    +     * 
    + * + * optional uint32 parent_id = 2; + */ + private int parentId; + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + */ + private final Utf8String name = Utf8String.newEmptyInstance(); + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + */ + private final RepeatedMessage requirements = RepeatedMessage.newEmptyInstance(ProtobufMechanism.getFactory()); + + private ProtobufCommand() { + } + + /** + * @return a new empty instance of {@code ProtobufCommand} + */ + public static ProtobufCommand newInstance() { + return new ProtobufCommand(); + } + + /** + *
    +     *  How much time the command took to execute in its most recent run.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double last_time_ms = 6; + * @return whether the lastTimeMs field is set + */ + public boolean hasLastTimeMs() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + *
    +     *  How much time the command took to execute in its most recent run.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double last_time_ms = 6; + * @return this + */ + public ProtobufCommand clearLastTimeMs() { + bitField0_ &= ~0x00000002; + lastTimeMs = 0D; + return this; + } + + /** + *
    +     *  How much time the command took to execute in its most recent run.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double last_time_ms = 6; + * @return the lastTimeMs + */ + public double getLastTimeMs() { + return lastTimeMs; + } + + /** + *
    +     *  How much time the command took to execute in its most recent run.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double last_time_ms = 6; + * @param value the lastTimeMs to set + * @return this + */ + public ProtobufCommand setLastTimeMs(final double value) { + bitField0_ |= 0x00000002; + lastTimeMs = value; + return this; + } + + /** + *
    +     *  How long the command has taken to run, in aggregate.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double total_time_ms = 7; + * @return whether the totalTimeMs field is set + */ + public boolean hasTotalTimeMs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + *
    +     *  How long the command has taken to run, in aggregate.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double total_time_ms = 7; + * @return this + */ + public ProtobufCommand clearTotalTimeMs() { + bitField0_ &= ~0x00000001; + totalTimeMs = 0D; + return this; + } + + /** + *
    +     *  How long the command has taken to run, in aggregate.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double total_time_ms = 7; + * @return the totalTimeMs + */ + public double getTotalTimeMs() { + return totalTimeMs; + } + + /** + *
    +     *  How long the command has taken to run, in aggregate.
    +     *  Only included in a message for an actively running command.
    +     * 
    + * + * optional double total_time_ms = 7; + * @param value the totalTimeMs to set + * @return this + */ + public ProtobufCommand setTotalTimeMs(final double value) { + bitField0_ |= 0x00000001; + totalTimeMs = value; + return this; + } + + /** + *
    +     *  The priority level of the command.
    +     * 
    + * + * optional int32 priority = 4; + * @return whether the priority field is set + */ + public boolean hasPriority() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + *
    +     *  The priority level of the command.
    +     * 
    + * + * optional int32 priority = 4; + * @return this + */ + public ProtobufCommand clearPriority() { + bitField0_ &= ~0x00000008; + priority = 0; + return this; + } + + /** + *
    +     *  The priority level of the command.
    +     * 
    + * + * optional int32 priority = 4; + * @return the priority + */ + public int getPriority() { + return priority; + } + + /** + *
    +     *  The priority level of the command.
    +     * 
    + * + * optional int32 priority = 4; + * @param value the priority to set + * @return this + */ + public ProtobufCommand setPriority(final int value) { + bitField0_ |= 0x00000008; + priority = value; + return this; + } + + /** + *
    +     *  A unique ID for the command.
    +     *  Different invocations of the same command object have different IDs.
    +     * 
    + * + * optional uint32 id = 1; + * @return whether the id field is set + */ + public boolean hasId() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + *
    +     *  A unique ID for the command.
    +     *  Different invocations of the same command object have different IDs.
    +     * 
    + * + * optional uint32 id = 1; + * @return this + */ + public ProtobufCommand clearId() { + bitField0_ &= ~0x00000010; + id = 0; + return this; + } + + /** + *
    +     *  A unique ID for the command.
    +     *  Different invocations of the same command object have different IDs.
    +     * 
    + * + * optional uint32 id = 1; + * @return the id + */ + public int getId() { + return id; + } + + /** + *
    +     *  A unique ID for the command.
    +     *  Different invocations of the same command object have different IDs.
    +     * 
    + * + * optional uint32 id = 1; + * @param value the id to set + * @return this + */ + public ProtobufCommand setId(final int value) { + bitField0_ |= 0x00000010; + id = value; + return this; + } + + /** + *
    +     *  The ID of the parent command.
    +     *  Not included in the message for top-level commands.
    +     * 
    + * + * optional uint32 parent_id = 2; + * @return whether the parentId field is set + */ + public boolean hasParentId() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + *
    +     *  The ID of the parent command.
    +     *  Not included in the message for top-level commands.
    +     * 
    + * + * optional uint32 parent_id = 2; + * @return this + */ + public ProtobufCommand clearParentId() { + bitField0_ &= ~0x00000004; + parentId = 0; + return this; + } + + /** + *
    +     *  The ID of the parent command.
    +     *  Not included in the message for top-level commands.
    +     * 
    + * + * optional uint32 parent_id = 2; + * @return the parentId + */ + public int getParentId() { + return parentId; + } + + /** + *
    +     *  The ID of the parent command.
    +     *  Not included in the message for top-level commands.
    +     * 
    + * + * optional uint32 parent_id = 2; + * @param value the parentId to set + * @return this + */ + public ProtobufCommand setParentId(final int value) { + bitField0_ |= 0x00000004; + parentId = value; + return this; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @return whether the name field is set + */ + public boolean hasName() { + return (bitField0_ & 0x00000020) != 0; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @return this + */ + public ProtobufCommand clearName() { + bitField0_ &= ~0x00000020; + name.clear(); + return this; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @return the name + */ + public String getName() { + return name.getString(); + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @return internal {@code Utf8String} representation of name for reading + */ + public Utf8String getNameBytes() { + return this.name; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @return internal {@code Utf8String} representation of name for modifications + */ + public Utf8String getMutableNameBytes() { + bitField0_ |= 0x00000020; + return this.name; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @param value the name to set + * @return this + */ + public ProtobufCommand setName(final CharSequence value) { + bitField0_ |= 0x00000020; + name.copyFrom(value); + return this; + } + + /** + *
    +     *  The name of the command.
    +     * 
    + * + * optional string name = 3; + * @param value the name to set + * @return this + */ + public ProtobufCommand setName(final Utf8String value) { + bitField0_ |= 0x00000020; + name.copyFrom(value); + return this; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * @return whether the requirements field is set + */ + public boolean hasRequirements() { + return (bitField0_ & 0x00000040) != 0; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * @return this + */ + public ProtobufCommand clearRequirements() { + bitField0_ &= ~0x00000040; + requirements.clear(); + return this; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRequirements()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getRequirements() { + return requirements; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableRequirements() { + bitField0_ |= 0x00000040; + return requirements; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * @param value the requirements to add + * @return this + */ + public ProtobufCommand addRequirements(final ProtobufMechanism value) { + bitField0_ |= 0x00000040; + requirements.add(value); + return this; + } + + /** + *
    +     *  The mechanisms required by the command.
    +     * 
    + * + * repeated .wpi.proto.ProtobufMechanism requirements = 5; + * @param values the requirements to add + * @return this + */ + public ProtobufCommand addAllRequirements(final ProtobufMechanism... values) { + bitField0_ |= 0x00000040; + requirements.addAll(values); + return this; + } + + @Override + public ProtobufCommand copyFrom(final ProtobufCommand other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + lastTimeMs = other.lastTimeMs; + totalTimeMs = other.totalTimeMs; + priority = other.priority; + id = other.id; + parentId = other.parentId; + name.copyFrom(other.name); + requirements.copyFrom(other.requirements); + } + return this; + } + + @Override + public ProtobufCommand mergeFrom(final ProtobufCommand other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasLastTimeMs()) { + setLastTimeMs(other.lastTimeMs); + } + if (other.hasTotalTimeMs()) { + setTotalTimeMs(other.totalTimeMs); + } + if (other.hasPriority()) { + setPriority(other.priority); + } + if (other.hasId()) { + setId(other.id); + } + if (other.hasParentId()) { + setParentId(other.parentId); + } + if (other.hasName()) { + getMutableNameBytes().copyFrom(other.name); + } + if (other.hasRequirements()) { + getMutableRequirements().addAll(other.requirements); + } + return this; + } + + @Override + public ProtobufCommand clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + lastTimeMs = 0D; + totalTimeMs = 0D; + priority = 0; + id = 0; + parentId = 0; + name.clear(); + requirements.clear(); + return this; + } + + @Override + public ProtobufCommand clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + name.clear(); + requirements.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufCommand)) { + return false; + } + ProtobufCommand other = (ProtobufCommand) o; + return bitField0_ == other.bitField0_ + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) + && (!hasTotalTimeMs() || ProtoUtil.isEqual(totalTimeMs, other.totalTimeMs)) + && (!hasPriority() || priority == other.priority) + && (!hasId() || id == other.id) + && (!hasParentId() || parentId == other.parentId) + && (!hasName() || name.equals(other.name)) + && (!hasRequirements() || requirements.equals(other.requirements)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 49); + output.writeDoubleNoTag(lastTimeMs); + } + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 57); + output.writeDoubleNoTag(totalTimeMs); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 32); + output.writeInt32NoTag(priority); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRawByte((byte) 8); + output.writeUInt32NoTag(id); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 16); + output.writeUInt32NoTag(parentId); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeRawByte((byte) 26); + output.writeStringNoTag(name); + } + if ((bitField0_ & 0x00000040) != 0) { + for (int i = 0; i < requirements.length(); i++) { + output.writeRawByte((byte) 42); + output.writeMessageNoTag(requirements.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 1 + ProtoSink.computeInt32SizeNoTag(priority); + } + if ((bitField0_ & 0x00000010) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(id); + } + if ((bitField0_ & 0x00000004) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(parentId); + } + if ((bitField0_ & 0x00000020) != 0) { + size += 1 + ProtoSink.computeStringSizeNoTag(name); + } + if ((bitField0_ & 0x00000040) != 0) { + size += (1 * requirements.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(requirements); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufCommand mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 49: { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 57) { + break; + } + } + case 57: { + // totalTimeMs + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 32) { + break; + } + } + case 32: { + // priority + priority = input.readInt32(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 8) { + break; + } + } + case 8: { + // id + id = input.readUInt32(); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 16) { + break; + } + } + case 16: { + // parentId + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: { + // name + input.readString(name); + bitField0_ |= 0x00000020; + tag = input.readTag(); + if (tag != 42) { + break; + } + } + case 42: { + // requirements + tag = input.readRepeatedMessage(requirements, tag); + bitField0_ |= 0x00000040; + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); + } + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.totalTimeMs, totalTimeMs); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeInt32(FieldNames.priority, priority); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeUInt32(FieldNames.id, id); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeUInt32(FieldNames.parentId, parentId); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeString(FieldNames.name, name); + } + if ((bitField0_ & 0x00000040) != 0) { + output.writeRepeatedMessage(FieldNames.requirements, requirements); + } + output.endObject(); + } + + @Override + public ProtobufCommand mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1958056841: + case -740797521: { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -717217353: + case 1006112349: { + if (input.isAtField(FieldNames.totalTimeMs)) { + if (!input.trySkipNullValue()) { + totalTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1165461084: { + if (input.isAtField(FieldNames.priority)) { + if (!input.trySkipNullValue()) { + priority = input.readInt32(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3355: { + if (input.isAtField(FieldNames.id)) { + if (!input.trySkipNullValue()) { + id = input.readUInt32(); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + case 1175162725: + case 2070327504: { + if (input.isAtField(FieldNames.parentId)) { + if (!input.trySkipNullValue()) { + parentId = input.readUInt32(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3373707: { + if (input.isAtField(FieldNames.name)) { + if (!input.trySkipNullValue()) { + input.readString(name); + bitField0_ |= 0x00000020; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1619874672: { + if (input.isAtField(FieldNames.requirements)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(requirements); + bitField0_ |= 0x00000040; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufCommand clone() { + return new ProtobufCommand().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufCommand parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), data).checkInitialized(); + } + + public static ProtobufCommand parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); + } + + public static ProtobufCommand parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCommand(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufCommand messages + */ + public static MessageFactory getFactory() { + return ProtobufCommandFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return ProtobufCommands.wpi_proto_ProtobufCommand_descriptor; + } + + private enum ProtobufCommandFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufCommand create() { + return ProtobufCommand.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); + + static final FieldName totalTimeMs = FieldName.forField("totalTimeMs", "total_time_ms"); + + static final FieldName priority = FieldName.forField("priority"); + + static final FieldName id = FieldName.forField("id"); + + static final FieldName parentId = FieldName.forField("parentId", "parent_id"); + + static final FieldName name = FieldName.forField("name"); + + static final FieldName requirements = FieldName.forField("requirements"); + } + } + + /** + * Protobuf type {@code ProtobufScheduler} + */ + public static final class ProtobufScheduler extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + *
    +     *  How much time the scheduler took in its last `run()` invocation.
    +     * 
    + * + * optional double last_time_ms = 3; + */ + private double lastTimeMs; + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + */ + private final RepeatedMessage queuedCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + */ + private final RepeatedMessage runningCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); + + private ProtobufScheduler() { + } + + /** + * @return a new empty instance of {@code ProtobufScheduler} + */ + public static ProtobufScheduler newInstance() { + return new ProtobufScheduler(); + } + + /** + *
    +     *  How much time the scheduler took in its last `run()` invocation.
    +     * 
    + * + * optional double last_time_ms = 3; + * @return whether the lastTimeMs field is set + */ + public boolean hasLastTimeMs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + *
    +     *  How much time the scheduler took in its last `run()` invocation.
    +     * 
    + * + * optional double last_time_ms = 3; + * @return this + */ + public ProtobufScheduler clearLastTimeMs() { + bitField0_ &= ~0x00000001; + lastTimeMs = 0D; + return this; + } + + /** + *
    +     *  How much time the scheduler took in its last `run()` invocation.
    +     * 
    + * + * optional double last_time_ms = 3; + * @return the lastTimeMs + */ + public double getLastTimeMs() { + return lastTimeMs; + } + + /** + *
    +     *  How much time the scheduler took in its last `run()` invocation.
    +     * 
    + * + * optional double last_time_ms = 3; + * @param value the lastTimeMs to set + * @return this + */ + public ProtobufScheduler setLastTimeMs(final double value) { + bitField0_ |= 0x00000001; + lastTimeMs = value; + return this; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * @return whether the queuedCommands field is set + */ + public boolean hasQueuedCommands() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * @return this + */ + public ProtobufScheduler clearQueuedCommands() { + bitField0_ &= ~0x00000002; + queuedCommands.clear(); + return this; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableQueuedCommands()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getQueuedCommands() { + return queuedCommands; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableQueuedCommands() { + bitField0_ |= 0x00000002; + return queuedCommands; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * @param value the queuedCommands to add + * @return this + */ + public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { + bitField0_ |= 0x00000002; + queuedCommands.add(value); + return this; + } + + /** + *
    +     *  Note: commands are generally queued by triggers, which occurs immediately before they are
    +     *  promoted and start running. Entries will only appear here when serializing a scheduler
    +     *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    +     * 
    + * + * repeated .wpi.proto.ProtobufCommand queued_commands = 1; + * @param values the queuedCommands to add + * @return this + */ + public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { + bitField0_ |= 0x00000002; + queuedCommands.addAll(values); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * @return whether the runningCommands field is set + */ + public boolean hasRunningCommands() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * @return this + */ + public ProtobufScheduler clearRunningCommands() { + bitField0_ &= ~0x00000004; + runningCommands.clear(); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRunningCommands()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getRunningCommands() { + return runningCommands; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableRunningCommands() { + bitField0_ |= 0x00000004; + return runningCommands; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * @param value the runningCommands to add + * @return this + */ + public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { + bitField0_ |= 0x00000004; + runningCommands.add(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufCommand running_commands = 2; + * @param values the runningCommands to add + * @return this + */ + public ProtobufScheduler addAllRunningCommands(final ProtobufCommand... values) { + bitField0_ |= 0x00000004; + runningCommands.addAll(values); + return this; + } + + @Override + public ProtobufScheduler copyFrom(final ProtobufScheduler other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + lastTimeMs = other.lastTimeMs; + queuedCommands.copyFrom(other.queuedCommands); + runningCommands.copyFrom(other.runningCommands); + } + return this; + } + + @Override + public ProtobufScheduler mergeFrom(final ProtobufScheduler other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasLastTimeMs()) { + setLastTimeMs(other.lastTimeMs); + } + if (other.hasQueuedCommands()) { + getMutableQueuedCommands().addAll(other.queuedCommands); + } + if (other.hasRunningCommands()) { + getMutableRunningCommands().addAll(other.runningCommands); + } + return this; + } + + @Override + public ProtobufScheduler clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + lastTimeMs = 0D; + queuedCommands.clear(); + runningCommands.clear(); + return this; + } + + @Override + public ProtobufScheduler clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + queuedCommands.clearQuick(); + runningCommands.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufScheduler)) { + return false; + } + ProtobufScheduler other = (ProtobufScheduler) o; + return bitField0_ == other.bitField0_ + && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) + && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) + && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(lastTimeMs); + } + if ((bitField0_ & 0x00000002) != 0) { + for (int i = 0; i < queuedCommands.length(); i++) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(queuedCommands.get(i)); + } + } + if ((bitField0_ & 0x00000004) != 0) { + for (int i = 0; i < runningCommands.length(); i++) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(runningCommands.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); + } + if ((bitField0_ & 0x00000004) != 0) { + size += (1 * runningCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 25: { + // lastTimeMs + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 10) { + break; + } + } + case 10: { + // queuedCommands + tag = input.readRepeatedMessage(queuedCommands, tag); + bitField0_ |= 0x00000002; + if (tag != 18) { + break; + } + } + case 18: { + // runningCommands + tag = input.readRepeatedMessage(runningCommands, tag); + bitField0_ |= 0x00000004; + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRepeatedMessage(FieldNames.queuedCommands, queuedCommands); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRepeatedMessage(FieldNames.runningCommands, runningCommands); + } + output.endObject(); + } + + @Override + public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1958056841: + case -740797521: { + if (input.isAtField(FieldNames.lastTimeMs)) { + if (!input.trySkipNullValue()) { + lastTimeMs = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -167160549: + case -1904270380: { + if (input.isAtField(FieldNames.queuedCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(queuedCommands); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1719052953: + case 1526672648: { + if (input.isAtField(FieldNames.runningCommands)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(runningCommands); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufScheduler clone() { + return new ProtobufScheduler().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufScheduler parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), data).checkInitialized(); + } + + public static ProtobufScheduler parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); + } + + public static ProtobufScheduler parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufScheduler messages + */ + public static MessageFactory getFactory() { + return ProtobufSchedulerFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return ProtobufCommands.wpi_proto_ProtobufScheduler_descriptor; + } + + private enum ProtobufSchedulerFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufScheduler create() { + return ProtobufScheduler.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); + + static final FieldName queuedCommands = FieldName.forField("queuedCommands", "queued_commands"); + + static final FieldName runningCommands = FieldName.forField("runningCommands", "running_commands"); + } + } +} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java deleted file mode 100644 index 8c631bbe517..00000000000 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufMechanism.java +++ /dev/null @@ -1,299 +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. -// Code generated by protocol buffer compiler. Do not edit! -package org.wpilib.commands3.proto; - -import java.io.IOException; -import us.hebi.quickbuf.Descriptors; -import us.hebi.quickbuf.FieldName; -import us.hebi.quickbuf.InvalidProtocolBufferException; -import us.hebi.quickbuf.JsonSink; -import us.hebi.quickbuf.JsonSource; -import us.hebi.quickbuf.MessageFactory; -import us.hebi.quickbuf.ProtoMessage; -import us.hebi.quickbuf.ProtoSink; -import us.hebi.quickbuf.ProtoSource; -import us.hebi.quickbuf.Utf8String; - -/** - * Protobuf type {@code ProtobufMechanism} - */ -@SuppressWarnings("hiding") -public final class ProtobufMechanism extends ProtoMessage implements Cloneable { - private static final long serialVersionUID = 0L; - - /** - * optional string name = 1; - */ - private final Utf8String name = Utf8String.newEmptyInstance(); - - private ProtobufMechanism() { - } - - /** - * @return a new empty instance of {@code ProtobufMechanism} - */ - public static ProtobufMechanism newInstance() { - return new ProtobufMechanism(); - } - - /** - * optional string name = 1; - * @return whether the name field is set - */ - public boolean hasName() { - return (bitField0_ & 0x00000001) != 0; - } - - /** - * optional string name = 1; - * @return this - */ - public ProtobufMechanism clearName() { - bitField0_ &= ~0x00000001; - name.clear(); - return this; - } - - /** - * optional string name = 1; - * @return the name - */ - public String getName() { - return name.getString(); - } - - /** - * optional string name = 1; - * @return internal {@code Utf8String} representation of name for reading - */ - public Utf8String getNameBytes() { - return this.name; - } - - /** - * optional string name = 1; - * @return internal {@code Utf8String} representation of name for modifications - */ - public Utf8String getMutableNameBytes() { - bitField0_ |= 0x00000001; - return this.name; - } - - /** - * optional string name = 1; - * @param value the name to set - * @return this - */ - public ProtobufMechanism setName(final CharSequence value) { - bitField0_ |= 0x00000001; - name.copyFrom(value); - return this; - } - - /** - * optional string name = 1; - * @param value the name to set - * @return this - */ - public ProtobufMechanism setName(final Utf8String value) { - bitField0_ |= 0x00000001; - name.copyFrom(value); - return this; - } - - @Override - public ProtobufMechanism copyFrom(final ProtobufMechanism other) { - cachedSize = other.cachedSize; - if ((bitField0_ | other.bitField0_) != 0) { - bitField0_ = other.bitField0_; - name.copyFrom(other.name); - } - return this; - } - - @Override - public ProtobufMechanism mergeFrom(final ProtobufMechanism other) { - if (other.isEmpty()) { - return this; - } - cachedSize = -1; - if (other.hasName()) { - getMutableNameBytes().copyFrom(other.name); - } - return this; - } - - @Override - public ProtobufMechanism clear() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - name.clear(); - return this; - } - - @Override - public ProtobufMechanism clearQuick() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - name.clear(); - return this; - } - - @Override - public boolean equals(Object o) { - if (o == this) { - return true; - } - if (!(o instanceof ProtobufMechanism)) { - return false; - } - ProtobufMechanism other = (ProtobufMechanism) o; - return bitField0_ == other.bitField0_ - && (!hasName() || name.equals(other.name)); - } - - @Override - public void writeTo(final ProtoSink output) throws IOException { - if ((bitField0_ & 0x00000001) != 0) { - output.writeRawByte((byte) 10); - output.writeStringNoTag(name); - } - } - - @Override - protected int computeSerializedSize() { - int size = 0; - if ((bitField0_ & 0x00000001) != 0) { - size += 1 + ProtoSink.computeStringSizeNoTag(name); - } - return size; - } - - @Override - @SuppressWarnings("fallthrough") - public ProtobufMechanism mergeFrom(final ProtoSource input) throws IOException { - // Enabled Fall-Through Optimization (QuickBuffers) - int tag = input.readTag(); - while (true) { - switch (tag) { - case 10: { - // name - input.readString(name); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 0) { - break; - } - } - case 0: { - return this; - } - default: { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } - } - } - } - - @Override - public void writeTo(final JsonSink output) throws IOException { - output.beginObject(); - if ((bitField0_ & 0x00000001) != 0) { - output.writeString(FieldNames.name, name); - } - output.endObject(); - } - - @Override - public ProtobufMechanism mergeFrom(final JsonSource input) throws IOException { - if (!input.beginObject()) { - return this; - } - while (!input.isAtEnd()) { - switch (input.readFieldHash()) { - case 3373707: { - if (input.isAtField(FieldNames.name)) { - if (!input.trySkipNullValue()) { - input.readString(name); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); - } - break; - } - default: { - input.skipUnknownField(); - break; - } - } - } - input.endObject(); - return this; - } - - @Override - public ProtobufMechanism clone() { - return new ProtobufMechanism().copyFrom(this); - } - - @Override - public boolean isEmpty() { - return ((bitField0_) == 0); - } - - public static ProtobufMechanism parseFrom(final byte[] data) throws - InvalidProtocolBufferException { - return ProtoMessage.mergeFrom(new ProtobufMechanism(), data).checkInitialized(); - } - - public static ProtobufMechanism parseFrom(final ProtoSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); - } - - public static ProtobufMechanism parseFrom(final JsonSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufMechanism(), input).checkInitialized(); - } - - /** - * @return factory for creating ProtobufMechanism messages - */ - public static MessageFactory getFactory() { - return ProtobufMechanismFactory.INSTANCE; - } - - /** - * @return this type's descriptor. - */ - public static Descriptors.Descriptor getDescriptor() { - return Scheduler.wpi_proto_ProtobufMechanism_descriptor; - } - - private enum ProtobufMechanismFactory implements MessageFactory { - INSTANCE; - - @Override - public ProtobufMechanism create() { - return ProtobufMechanism.newInstance(); - } - } - - /** - * Contains name constants used for serializing JSON - */ - static class FieldNames { - static final FieldName name = FieldName.forField("name"); - } -} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java deleted file mode 100644 index e73bbd5c9bb..00000000000 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufScheduler.java +++ /dev/null @@ -1,562 +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. -// Code generated by protocol buffer compiler. Do not edit! -package org.wpilib.commands3.proto; - -import java.io.IOException; -import us.hebi.quickbuf.Descriptors; -import us.hebi.quickbuf.FieldName; -import us.hebi.quickbuf.InvalidProtocolBufferException; -import us.hebi.quickbuf.JsonSink; -import us.hebi.quickbuf.JsonSource; -import us.hebi.quickbuf.MessageFactory; -import us.hebi.quickbuf.ProtoMessage; -import us.hebi.quickbuf.ProtoSink; -import us.hebi.quickbuf.ProtoSource; -import us.hebi.quickbuf.ProtoUtil; -import us.hebi.quickbuf.RepeatedMessage; - -/** - * Protobuf type {@code ProtobufScheduler} - */ -@SuppressWarnings("hiding") -public final class ProtobufScheduler extends ProtoMessage implements Cloneable { - private static final long serialVersionUID = 0L; - - /** - *
    -   *  How much time the scheduler took in its last `run()` invocation.
    -   * 
    - * - * optional double last_time_ms = 3; - */ - private double lastTimeMs; - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - */ - private final RepeatedMessage queuedCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - */ - private final RepeatedMessage runningCommands = RepeatedMessage.newEmptyInstance(ProtobufCommand.getFactory()); - - private ProtobufScheduler() { - } - - /** - * @return a new empty instance of {@code ProtobufScheduler} - */ - public static ProtobufScheduler newInstance() { - return new ProtobufScheduler(); - } - - /** - *
    -   *  How much time the scheduler took in its last `run()` invocation.
    -   * 
    - * - * optional double last_time_ms = 3; - * @return whether the lastTimeMs field is set - */ - public boolean hasLastTimeMs() { - return (bitField0_ & 0x00000001) != 0; - } - - /** - *
    -   *  How much time the scheduler took in its last `run()` invocation.
    -   * 
    - * - * optional double last_time_ms = 3; - * @return this - */ - public ProtobufScheduler clearLastTimeMs() { - bitField0_ &= ~0x00000001; - lastTimeMs = 0D; - return this; - } - - /** - *
    -   *  How much time the scheduler took in its last `run()` invocation.
    -   * 
    - * - * optional double last_time_ms = 3; - * @return the lastTimeMs - */ - public double getLastTimeMs() { - return lastTimeMs; - } - - /** - *
    -   *  How much time the scheduler took in its last `run()` invocation.
    -   * 
    - * - * optional double last_time_ms = 3; - * @param value the lastTimeMs to set - * @return this - */ - public ProtobufScheduler setLastTimeMs(final double value) { - bitField0_ |= 0x00000001; - lastTimeMs = value; - return this; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * @return whether the queuedCommands field is set - */ - public boolean hasQueuedCommands() { - return (bitField0_ & 0x00000002) != 0; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * @return this - */ - public ProtobufScheduler clearQueuedCommands() { - bitField0_ &= ~0x00000002; - queuedCommands.clear(); - return this; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * - * This method returns the internal storage object without modifying any has state. - * The returned object should not be modified and be treated as read-only. - * - * Use {@link #getMutableQueuedCommands()} if you want to modify it. - * - * @return internal storage object for reading - */ - public RepeatedMessage getQueuedCommands() { - return queuedCommands; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * - * This method returns the internal storage object and sets the corresponding - * has state. The returned object will become part of this message and its - * contents may be modified as long as the has state is not cleared. - * - * @return internal storage object for modifications - */ - public RepeatedMessage getMutableQueuedCommands() { - bitField0_ |= 0x00000002; - return queuedCommands; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * @param value the queuedCommands to add - * @return this - */ - public ProtobufScheduler addQueuedCommands(final ProtobufCommand value) { - bitField0_ |= 0x00000002; - queuedCommands.add(value); - return this; - } - - /** - *
    -   *  Note: commands are generally queued by triggers, which occurs immediately before they are
    -   *  promoted and start running. Entries will only appear here when serializing a scheduler
    -   *  _after_ manually scheduling a command but _before_ calling scheduler.run()
    -   * 
    - * - * repeated .wpi.proto.ProtobufCommand queued_commands = 1; - * @param values the queuedCommands to add - * @return this - */ - public ProtobufScheduler addAllQueuedCommands(final ProtobufCommand... values) { - bitField0_ |= 0x00000002; - queuedCommands.addAll(values); - return this; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * @return whether the runningCommands field is set - */ - public boolean hasRunningCommands() { - return (bitField0_ & 0x00000004) != 0; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * @return this - */ - public ProtobufScheduler clearRunningCommands() { - bitField0_ &= ~0x00000004; - runningCommands.clear(); - return this; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * - * This method returns the internal storage object without modifying any has state. - * The returned object should not be modified and be treated as read-only. - * - * Use {@link #getMutableRunningCommands()} if you want to modify it. - * - * @return internal storage object for reading - */ - public RepeatedMessage getRunningCommands() { - return runningCommands; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * - * This method returns the internal storage object and sets the corresponding - * has state. The returned object will become part of this message and its - * contents may be modified as long as the has state is not cleared. - * - * @return internal storage object for modifications - */ - public RepeatedMessage getMutableRunningCommands() { - bitField0_ |= 0x00000004; - return runningCommands; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * @param value the runningCommands to add - * @return this - */ - public ProtobufScheduler addRunningCommands(final ProtobufCommand value) { - bitField0_ |= 0x00000004; - runningCommands.add(value); - return this; - } - - /** - * repeated .wpi.proto.ProtobufCommand running_commands = 2; - * @param values the runningCommands to add - * @return this - */ - public ProtobufScheduler addAllRunningCommands(final ProtobufCommand... values) { - bitField0_ |= 0x00000004; - runningCommands.addAll(values); - return this; - } - - @Override - public ProtobufScheduler copyFrom(final ProtobufScheduler other) { - cachedSize = other.cachedSize; - if ((bitField0_ | other.bitField0_) != 0) { - bitField0_ = other.bitField0_; - lastTimeMs = other.lastTimeMs; - queuedCommands.copyFrom(other.queuedCommands); - runningCommands.copyFrom(other.runningCommands); - } - return this; - } - - @Override - public ProtobufScheduler mergeFrom(final ProtobufScheduler other) { - if (other.isEmpty()) { - return this; - } - cachedSize = -1; - if (other.hasLastTimeMs()) { - setLastTimeMs(other.lastTimeMs); - } - if (other.hasQueuedCommands()) { - getMutableQueuedCommands().addAll(other.queuedCommands); - } - if (other.hasRunningCommands()) { - getMutableRunningCommands().addAll(other.runningCommands); - } - return this; - } - - @Override - public ProtobufScheduler clear() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - lastTimeMs = 0D; - queuedCommands.clear(); - runningCommands.clear(); - return this; - } - - @Override - public ProtobufScheduler clearQuick() { - if (isEmpty()) { - return this; - } - cachedSize = -1; - bitField0_ = 0; - queuedCommands.clearQuick(); - runningCommands.clearQuick(); - return this; - } - - @Override - public boolean equals(Object o) { - if (o == this) { - return true; - } - if (!(o instanceof ProtobufScheduler)) { - return false; - } - ProtobufScheduler other = (ProtobufScheduler) o; - return bitField0_ == other.bitField0_ - && (!hasLastTimeMs() || ProtoUtil.isEqual(lastTimeMs, other.lastTimeMs)) - && (!hasQueuedCommands() || queuedCommands.equals(other.queuedCommands)) - && (!hasRunningCommands() || runningCommands.equals(other.runningCommands)); - } - - @Override - public void writeTo(final ProtoSink output) throws IOException { - if ((bitField0_ & 0x00000001) != 0) { - output.writeRawByte((byte) 25); - output.writeDoubleNoTag(lastTimeMs); - } - if ((bitField0_ & 0x00000002) != 0) { - for (int i = 0; i < queuedCommands.length(); i++) { - output.writeRawByte((byte) 10); - output.writeMessageNoTag(queuedCommands.get(i)); - } - } - if ((bitField0_ & 0x00000004) != 0) { - for (int i = 0; i < runningCommands.length(); i++) { - output.writeRawByte((byte) 18); - output.writeMessageNoTag(runningCommands.get(i)); - } - } - } - - @Override - protected int computeSerializedSize() { - int size = 0; - if ((bitField0_ & 0x00000001) != 0) { - size += 9; - } - if ((bitField0_ & 0x00000002) != 0) { - size += (1 * queuedCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(queuedCommands); - } - if ((bitField0_ & 0x00000004) != 0) { - size += (1 * runningCommands.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(runningCommands); - } - return size; - } - - @Override - @SuppressWarnings("fallthrough") - public ProtobufScheduler mergeFrom(final ProtoSource input) throws IOException { - // Enabled Fall-Through Optimization (QuickBuffers) - int tag = input.readTag(); - while (true) { - switch (tag) { - case 25: { - // lastTimeMs - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - tag = input.readTag(); - if (tag != 10) { - break; - } - } - case 10: { - // queuedCommands - tag = input.readRepeatedMessage(queuedCommands, tag); - bitField0_ |= 0x00000002; - if (tag != 18) { - break; - } - } - case 18: { - // runningCommands - tag = input.readRepeatedMessage(runningCommands, tag); - bitField0_ |= 0x00000004; - if (tag != 0) { - break; - } - } - case 0: { - return this; - } - default: { - if (!input.skipField(tag)) { - return this; - } - tag = input.readTag(); - break; - } - } - } - } - - @Override - public void writeTo(final JsonSink output) throws IOException { - output.beginObject(); - if ((bitField0_ & 0x00000001) != 0) { - output.writeDouble(FieldNames.lastTimeMs, lastTimeMs); - } - if ((bitField0_ & 0x00000002) != 0) { - output.writeRepeatedMessage(FieldNames.queuedCommands, queuedCommands); - } - if ((bitField0_ & 0x00000004) != 0) { - output.writeRepeatedMessage(FieldNames.runningCommands, runningCommands); - } - output.endObject(); - } - - @Override - public ProtobufScheduler mergeFrom(final JsonSource input) throws IOException { - if (!input.beginObject()) { - return this; - } - while (!input.isAtEnd()) { - switch (input.readFieldHash()) { - case 1958056841: - case -740797521: { - if (input.isAtField(FieldNames.lastTimeMs)) { - if (!input.trySkipNullValue()) { - lastTimeMs = input.readDouble(); - bitField0_ |= 0x00000001; - } - } else { - input.skipUnknownField(); - } - break; - } - case -167160549: - case -1904270380: { - if (input.isAtField(FieldNames.queuedCommands)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(queuedCommands); - bitField0_ |= 0x00000002; - } - } else { - input.skipUnknownField(); - } - break; - } - case -1719052953: - case 1526672648: { - if (input.isAtField(FieldNames.runningCommands)) { - if (!input.trySkipNullValue()) { - input.readRepeatedMessage(runningCommands); - bitField0_ |= 0x00000004; - } - } else { - input.skipUnknownField(); - } - break; - } - default: { - input.skipUnknownField(); - break; - } - } - } - input.endObject(); - return this; - } - - @Override - public ProtobufScheduler clone() { - return new ProtobufScheduler().copyFrom(this); - } - - @Override - public boolean isEmpty() { - return ((bitField0_) == 0); - } - - public static ProtobufScheduler parseFrom(final byte[] data) throws - InvalidProtocolBufferException { - return ProtoMessage.mergeFrom(new ProtobufScheduler(), data).checkInitialized(); - } - - public static ProtobufScheduler parseFrom(final ProtoSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); - } - - public static ProtobufScheduler parseFrom(final JsonSource input) throws IOException { - return ProtoMessage.mergeFrom(new ProtobufScheduler(), input).checkInitialized(); - } - - /** - * @return factory for creating ProtobufScheduler messages - */ - public static MessageFactory getFactory() { - return ProtobufSchedulerFactory.INSTANCE; - } - - /** - * @return this type's descriptor. - */ - public static Descriptors.Descriptor getDescriptor() { - return Scheduler.wpi_proto_ProtobufScheduler_descriptor; - } - - private enum ProtobufSchedulerFactory implements MessageFactory { - INSTANCE; - - @Override - public ProtobufScheduler create() { - return ProtobufScheduler.newInstance(); - } - } - - /** - * Contains name constants used for serializing JSON - */ - static class FieldNames { - static final FieldName lastTimeMs = FieldName.forField("lastTimeMs", "last_time_ms"); - - static final FieldName queuedCommands = FieldName.forField("queuedCommands", "queued_commands"); - - static final FieldName runningCommands = FieldName.forField("runningCommands", "running_commands"); - } -} diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.java deleted file mode 100644 index 6806fb867be..00000000000 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/Scheduler.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. -// Code generated by protocol buffer compiler. Do not edit! -package org.wpilib.commands3.proto; - -import us.hebi.quickbuf.Descriptors; -import us.hebi.quickbuf.ProtoUtil; -import us.hebi.quickbuf.RepeatedByte; - -public final class Scheduler { - private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2476, - "Cg9zY2hlZHVsZXIucHJvdG8SCXdwaS5wcm90byInChFQcm90b2J1Zk1lY2hhbmlzbRISCgRuYW1lGAEg" + - "ASgJUgRuYW1lIrYCCg9Qcm90b2J1ZkNvbW1hbmQSDgoCaWQYASABKA1SAmlkEiAKCXBhcmVudF9pZBgC" + - "IAEoDUgAUghwYXJlbnRJZIgBARISCgRuYW1lGAMgASgJUgRuYW1lEhoKCHByaW9yaXR5GAQgASgFUghw" + - "cmlvcml0eRJACgxyZXF1aXJlbWVudHMYBSADKAsyHC53cGkucHJvdG8uUHJvdG9idWZNZWNoYW5pc21S" + - "DHJlcXVpcmVtZW50cxIlCgxsYXN0X3RpbWVfbXMYBiABKAFIAVIKbGFzdFRpbWVNc4gBARInCg10b3Rh" + - "bF90aW1lX21zGAcgASgBSAJSC3RvdGFsVGltZU1ziAEBQgwKCl9wYXJlbnRfaWRCDwoNX2xhc3RfdGlt" + - "ZV9tc0IQCg5fdG90YWxfdGltZV9tcyLBAQoRUHJvdG9idWZTY2hlZHVsZXISQwoPcXVldWVkX2NvbW1h" + - "bmRzGAEgAygLMhoud3BpLnByb3RvLlByb3RvYnVmQ29tbWFuZFIOcXVldWVkQ29tbWFuZHMSRQoQcnVu" + - "bmluZ19jb21tYW5kcxgCIAMoCzIaLndwaS5wcm90by5Qcm90b2J1ZkNvbW1hbmRSD3J1bm5pbmdDb21t" + - "YW5kcxIgCgxsYXN0X3RpbWVfbXMYAyABKAFSCmxhc3RUaW1lTXNCHgoab3JnLndwaWxpYi5jb21tYW5k" + - "czMucHJvdG9QAUq/DgoGEgQAADUBCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAzCgkKAggBEgME" + - "ADMKCAoBCBIDBQAiCgkKAggKEgMFACIKnwEKAgQAEgQNAA8BMpIBCmFsbHdwaWxpYiAkIHByb3RvYy1x" + - "dWlja2J1ZiBcCi0tcXVpY2tidWZfb3V0PWdlbl9kZXNjcmlwdG9ycz10cnVlOmNvbW1hbmRzdjMvc3Jj" + - "L2dlbmVyYXRlZC9tYWluL2phdmEgXApjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3NjaGVkdWxlci5w" + - "cm90bwoKCgoDBAABEgMNCBkKCwoEBAACABIDDgISCgwKBQQAAgAFEgMOAggKDAoFBAACAAESAw4JDQoM" + - "CgUEAAIAAxIDDhARCgoKAgQBEgQRACoBCgoKAwQBARIDEQgXCnEKBAQBAgASAxQCEBpkIEEgdW5pcXVl" + - "IElEIGZvciB0aGUgY29tbWFuZC4KIERpZmZlcmVudCBpbnZvY2F0aW9ucyBvZiB0aGUgc2FtZSBjb21t" + - "YW5kIG9iamVjdCBoYXZlIGRpZmZlcmVudCBJRHMuCgoMCgUEAQIABRIDFAIICgwKBQQBAgABEgMUCQsK" + - "DAoFBAECAAMSAxQODwphCgQEAQIBEgMYAiAaVCBUaGUgSUQgb2YgdGhlIHBhcmVudCBjb21tYW5kLgog" + - "Tm90IGluY2x1ZGVkIGluIHRoZSBtZXNzYWdlIGZvciB0b3AtbGV2ZWwgY29tbWFuZHMuCgoMCgUEAQIB", - "BBIDGAIKCgwKBQQBAgEFEgMYCxEKDAoFBAECAQESAxgSGwoMCgUEAQIBAxIDGB4fCicKBAQBAgISAxsC" + - "EhoaIFRoZSBuYW1lIG9mIHRoZSBjb21tYW5kLgoKDAoFBAECAgUSAxsCCAoMCgUEAQICARIDGwkNCgwK" + - "BQQBAgIDEgMbEBEKMQoEBAECAxIDHgIVGiQgVGhlIHByaW9yaXR5IGxldmVsIG9mIHRoZSBjb21tYW5k" + - "LgoKDAoFBAECAwUSAx4CBwoMCgUEAQIDARIDHggQCgwKBQQBAgMDEgMeExQKNgoEBAECBBIDIQIuGikg" + - "VGhlIG1lY2hhbmlzbXMgcmVxdWlyZWQgYnkgdGhlIGNvbW1hbmQuCgoMCgUEAQIEBBIDIQIKCgwKBQQB" + - "AgQGEgMhCxwKDAoFBAECBAESAyEdKQoMCgUEAQIEAxIDISwtCo4BCgQEAQIFEgMlAiMagAEgSG93IG11" + - "Y2ggdGltZSB0aGUgY29tbWFuZCB0b29rIHRvIGV4ZWN1dGUgaW4gaXRzIG1vc3QgcmVjZW50IHJ1bi4K" + - "IE9ubHkgaW5jbHVkZWQgaW4gYSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQu" + - "CgoMCgUEAQIFBBIDJQIKCgwKBQQBAgUFEgMlCxEKDAoFBAECBQESAyUSHgoMCgUEAQIFAxIDJSEiCoAB" + - "CgQEAQIGEgMpAiQacyBIb3cgbG9uZyB0aGUgY29tbWFuZCBoYXMgdGFrZW4gdG8gcnVuLCBpbiBhZ2dy" + - "ZWdhdGUuCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZlbHkgcnVubmluZyBj" + - "b21tYW5kLgoKDAoFBAECBgQSAykCCgoMCgUEAQIGBRIDKQsRCgwKBQQBAgYBEgMpEh8KDAoFBAECBgMS" + - "AykiIwoKCgIEAhIELAA1AQoKCgMEAgESAywIGQqNAgoEBAICABIDMAIvGv8BIE5vdGU6IGNvbW1hbmRz" + - "IGFyZSBnZW5lcmFsbHkgcXVldWVkIGJ5IHRyaWdnZXJzLCB3aGljaCBvY2N1cnMgaW1tZWRpYXRlbHkg" + - "YmVmb3JlIHRoZXkgYXJlCiBwcm9tb3RlZCBhbmQgc3RhcnQgcnVubmluZy4gRW50cmllcyB3aWxsIG9u" + - "bHkgYXBwZWFyIGhlcmUgd2hlbiBzZXJpYWxpemluZyBhIHNjaGVkdWxlcgogX2FmdGVyXyBtYW51YWxs" + - "eSBzY2hlZHVsaW5nIGEgY29tbWFuZCBidXQgX2JlZm9yZV8gY2FsbGluZyBzY2hlZHVsZXIucnVuKCkK" + - "CgwKBQQCAgAEEgMwAgoKDAoFBAICAAYSAzALGgoMCgUEAgIAARIDMBsqCgwKBQQCAgADEgMwLS4KCwoE" + - "BAICARIDMQIwCgwKBQQCAgEEEgMxAgoKDAoFBAICAQYSAzELGgoMCgUEAgIBARIDMRsrCgwKBQQCAgED" + - "EgMxLi8KTwoEBAICAhIDNAIaGkIgSG93IG11Y2ggdGltZSB0aGUgc2NoZWR1bGVyIHRvb2sgaW4gaXRz", - "IGxhc3QgYHJ1bigpYCBpbnZvY2F0aW9uLgoKDAoFBAICAgUSAzQCCAoMCgUEAgICARIDNAkVCgwKBQQC" + - "AgIDEgM0GBliBnByb3RvMw=="); - - static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("scheduler.proto", "wpi.proto", descriptorData); - - static final Descriptors.Descriptor wpi_proto_ProtobufMechanism_descriptor = descriptor.internalContainedType(30, 39, "ProtobufMechanism", "wpi.proto.ProtobufMechanism"); - - static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(72, 310, "ProtobufCommand", "wpi.proto.ProtobufCommand"); - - static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(385, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); - - /** - * @return this proto file's descriptor. - */ - public static Descriptors.FileDescriptor getDescriptor() { - return descriptor; - } -} diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java index 5d48485b04c..f8fe21f7716 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/CommandProto.java @@ -6,7 +6,9 @@ import edu.wpi.first.util.protobuf.Protobuf; import org.wpilib.commands3.Command; +import org.wpilib.commands3.Mechanism; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.proto.ProtobufCommands.ProtobufCommand; import us.hebi.quickbuf.Descriptors; /** Protobuf serde for running commands. */ @@ -40,6 +42,8 @@ public Command unpack(ProtobufCommand msg) { @Override public void pack(ProtobufCommand msg, Command command) { + msg.clear(); + msg.setId(m_scheduler.runId(command)); Command parent = m_scheduler.getParentOf(command); if (parent != null) { @@ -48,12 +52,10 @@ public void pack(ProtobufCommand msg, Command command) { msg.setName(command.name()); msg.setPriority(command.priority()); - for (var requirement : command.requirements()) { - var rrp = new MechanismProto(); - ProtobufMechanism requirementMessage = rrp.createMessage(); - rrp.pack(requirementMessage, requirement); - msg.addRequirements(requirementMessage); - } + Protobuf.packArray( + msg.getMutableRequirements(), + command.requirements().toArray(new Mechanism[0]), + new MechanismProto()); if (m_scheduler.isRunning(command)) { msg.setLastTimeMs(m_scheduler.lastCommandRuntimeMs(command)); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java index 42236110425..5e469d2d54a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/MechanismProto.java @@ -6,6 +6,7 @@ import edu.wpi.first.util.protobuf.Protobuf; import org.wpilib.commands3.Mechanism; +import org.wpilib.commands3.proto.ProtobufCommands.ProtobufMechanism; import us.hebi.quickbuf.Descriptors; public class MechanismProto implements Protobuf { @@ -31,6 +32,7 @@ public Mechanism unpack(ProtobufMechanism msg) { @Override public void pack(ProtobufMechanism msg, Mechanism value) { + msg.clear(); msg.setName(value.getName()); } } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java index 5f93ecc7dd0..bc5ad124c4b 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/proto/SchedulerProto.java @@ -5,7 +5,9 @@ package org.wpilib.commands3.proto; import edu.wpi.first.util.protobuf.Protobuf; +import org.wpilib.commands3.Command; import org.wpilib.commands3.Scheduler; +import org.wpilib.commands3.proto.ProtobufCommands.ProtobufScheduler; import us.hebi.quickbuf.Descriptors; /** @@ -37,19 +39,19 @@ public Scheduler unpack(ProtobufScheduler msg) { @Override public void pack(ProtobufScheduler msg, Scheduler scheduler) { - var cp = new CommandProto(scheduler); - - for (var command : scheduler.getQueuedCommands()) { - ProtobufCommand commandMessage = cp.createMessage(); - cp.pack(commandMessage, command); - msg.addQueuedCommands(commandMessage); - } - - for (var command : scheduler.getRunningCommands()) { - ProtobufCommand commandMessage = cp.createMessage(); - cp.pack(commandMessage, command); - msg.addRunningCommands(commandMessage); - } + msg.clear(); + + var commandProto = new CommandProto(scheduler); + + Protobuf.packArray( + msg.getMutableQueuedCommands(), + scheduler.getQueuedCommands().toArray(new Command[0]), + commandProto); + + Protobuf.packArray( + msg.getMutableRunningCommands(), + scheduler.getRunningCommands().toArray(new Command[0]), + commandProto); msg.setLastTimeMs(scheduler.lastRuntimeMs()); } diff --git a/commandsv3/src/main/proto/scheduler.proto b/commandsv3/src/main/proto/protobuf_commands.proto similarity index 94% rename from commandsv3/src/main/proto/scheduler.proto rename to commandsv3/src/main/proto/protobuf_commands.proto index 9d9b7d82f41..a23cf90ce4d 100644 --- a/commandsv3/src/main/proto/scheduler.proto +++ b/commandsv3/src/main/proto/protobuf_commands.proto @@ -3,12 +3,11 @@ syntax = "proto3"; package wpi.proto; option java_package = "org.wpilib.commands3.proto"; -option java_multiple_files = true; /* allwpilib $ protoc-quickbuf \ --quickbuf_out=gen_descriptors=true:commandsv3/src/generated/main/java \ - commandsv3/src/main/proto/scheduler.proto + commandsv3/src/main/proto/protobuf_commands.proto */ message ProtobufMechanism { diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java index 9f16e7c5bec..e88507b62a4 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java @@ -36,11 +36,13 @@ void protobuf() { "queuedCommands": [{ "priority": 0, "id": %s, - "name": "Command 1" + "name": "Command 1", + "requirements": [] }, { "priority": 0, "id": %s, - "name": "Command 2" + "name": "Command 2", + "requirements": [] }], "runningCommands": [{ "lastTimeMs": %s, From 66856bfe55db1770fb86b50dcb0a7b302bd15b22 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 11:35:10 -0400 Subject: [PATCH 129/153] Rename test files --- ...est_Cancellation.java => SchedulerCancellationTests.java} | 3 +-- ...edulerTest_Conflicts.java => SchedulerConflictTests.java} | 3 +-- ...ulerTest_Errors.java => SchedulerErrorHandlingTests.java} | 5 ++--- ...Test_Priorities.java => SchedulerPriorityLevelTests.java} | 3 +-- ...st_Sideloads.java => SchedulerSideloadFunctionTests.java} | 3 +-- ...dulerTest_Telemetry.java => SchedulerTelemetryTests.java} | 3 +-- .../{SchedulerTest_Timing.java => SchedulerTimingTests.java} | 3 +-- 7 files changed, 8 insertions(+), 15 deletions(-) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Cancellation.java => SchedulerCancellationTests.java} (99%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Conflicts.java => SchedulerConflictTests.java} (98%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Errors.java => SchedulerErrorHandlingTests.java} (97%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Priorities.java => SchedulerPriorityLevelTests.java} (95%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Sideloads.java => SchedulerSideloadFunctionTests.java} (97%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Telemetry.java => SchedulerTelemetryTests.java} (97%) rename commandsv3/src/test/java/org/wpilib/commands3/{SchedulerTest_Timing.java => SchedulerTimingTests.java} (98%) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java similarity index 99% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java index 949833cd11d..2644386d522 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Cancellation.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java @@ -18,8 +18,7 @@ import java.util.concurrent.atomic.AtomicReference; import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Cancellation extends CommandTestBase { +class SchedulerCancellationTests extends CommandTestBase { @Test void cancelOnInterruptDoesNotResume() { var count = new AtomicInteger(0); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java similarity index 98% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java index 15784af400e..2a339822b51 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Conflicts.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java @@ -14,8 +14,7 @@ import java.util.function.Supplier; import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Conflicts extends CommandTestBase { +class SchedulerConflictTests extends CommandTestBase { @Test void compositionsCannotAwaitConflictingCommands() { var mech = new Mechanism("The Mechanism", m_scheduler); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java similarity index 97% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java index bbc5c5d40ea..a732f05e362 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Errors.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java @@ -13,8 +13,7 @@ import java.util.ArrayList; import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Errors extends CommandTestBase { +class SchedulerErrorHandlingTests extends CommandTestBase { @Test @SuppressWarnings("PMD.AvoidCatchingGenericException") void errorDetection() { @@ -37,7 +36,7 @@ void errorDetection() { assertEquals("The exception", e.getMessage()); assertEquals( - "org.wpilib.commands3.SchedulerTest_Errors", e.getStackTrace()[0].getClassName()); + "org.wpilib.commands3.SchedulerErrorHandlingTests", e.getStackTrace()[0].getClassName()); assertEquals("lambda$errorDetection$0", e.getStackTrace()[0].getMethodName()); assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java similarity index 95% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java index 534ca1cdce5..4c66f41edaf 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Priorities.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java @@ -10,8 +10,7 @@ import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Priorities extends CommandTestBase { +class SchedulerPriorityLevelTests extends CommandTestBase { @Test void higherPriorityCancels() { final var subsystem = new Mechanism("Subsystem", m_scheduler); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerSideloadFunctionTests.java similarity index 97% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerSideloadFunctionTests.java index 7fa5bf74bb5..958005e5e7e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Sideloads.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerSideloadFunctionTests.java @@ -13,8 +13,7 @@ import java.util.concurrent.atomic.AtomicInteger; import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Sideloads extends CommandTestBase { +class SchedulerSideloadFunctionTests extends CommandTestBase { @Test void sideloadThrowingException() { m_scheduler.sideload( diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java similarity index 97% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java index e88507b62a4..9c7f07bff4f 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Telemetry.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java @@ -8,8 +8,7 @@ import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Telemetry extends CommandTestBase { +class SchedulerTelemetryTests extends CommandTestBase { @Test void protobuf() { var mech = new Mechanism("The mechanism", m_scheduler); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java similarity index 98% rename from commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java rename to commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java index fdc0f3955cb..ecd49a225a7 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest_Timing.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java @@ -18,8 +18,7 @@ import java.util.concurrent.atomic.AtomicReference; import org.junit.jupiter.api.Test; -@SuppressWarnings("checkstyle:TypeName") -class SchedulerTest_Timing extends CommandTestBase { +class SchedulerTimingTests extends CommandTestBase { @Test void commandAwaitingItself() { // This command deadlocks on itself. It's calling yield() in an infinite loop, which is From 02aa15fdc914bffa45ce492f4297bc365c4880c9 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 11:57:11 -0400 Subject: [PATCH 130/153] Test cleanup Standardize on assertThrows Add explicit check to ParallelGroupTest --- .../org/wpilib/commands3/CoroutineTest.java | 36 ++++------ .../wpilib/commands3/ParallelGroupTest.java | 7 +- .../SchedulerErrorHandlingTests.java | 66 ++++++++----------- 3 files changed, 40 insertions(+), 69 deletions(-) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java index 9691fb8b507..b6779f8a9a6 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CoroutineTest.java @@ -5,8 +5,8 @@ package org.wpilib.commands3; import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertThrows; import static org.junit.jupiter.api.Assertions.assertTrue; -import static org.junit.jupiter.api.Assertions.fail; import java.util.Set; import java.util.concurrent.atomic.AtomicBoolean; @@ -59,16 +59,12 @@ void yieldInSynchronizedBlock() { m_scheduler.schedule(yieldInSynchronized); - try { - m_scheduler.run(); - fail("Monitor pinned exception should have been thrown"); - } catch (IllegalStateException expected) { - assertEquals( - "Coroutine.yield() cannot be called inside a synchronized block or method. " - + "Consider using a Lock instead of synchronized, " - + "or rewrite your code to avoid locks and mutexes altogether.", - expected.getMessage()); - } + var error = assertThrows(IllegalStateException.class, m_scheduler::run); + assertEquals( + "Coroutine.yield() cannot be called inside a synchronized block or method. " + + "Consider using a Lock instead of synchronized, " + + "or rewrite your code to avoid locks and mutexes altogether.", + error.getMessage()); } @Test @@ -112,13 +108,8 @@ void coroutineEscapingCommand() { m_scheduler.schedule(badCommand); m_scheduler.run(); - try { - escapeeCallback.get().run(); - fail("Calling coroutine.yield() outside of a command should error"); - } catch (IllegalStateException expected) { - assertEquals( - "Coroutines can only be used by the command bound to them", expected.getMessage()); - } + var error = assertThrows(IllegalStateException.class, escapeeCallback.get()::run); + assertEquals("Coroutines can only be used by the command bound to them", error.getMessage()); } @Test @@ -138,13 +129,8 @@ void usingParentCoroutineInChildThrows() { .named("Parent"); m_scheduler.schedule(parent); - try { - m_scheduler.run(); - fail("Calling parentCoroutine.yield() in a child command should error"); - } catch (IllegalStateException expected) { - assertEquals( - "Coroutines can only be used by the command bound to them", expected.getMessage()); - } + var error = assertThrows(IllegalStateException.class, m_scheduler::run); + assertEquals("Coroutines can only be used by the command bound to them", error.getMessage()); } @Test diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index b0189c78b2a..0e711102147 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -66,13 +66,12 @@ void parallelAll() { assertEquals(5, c1Count.get()); assertEquals(i, c2Count.get()); } - // one final run() should unschedule the c2 command + + // one final run() should unschedule the c2 command and end the group + assertTrue(m_scheduler.isRunning(parallel)); m_scheduler.run(); assertFalse(m_scheduler.isRunning(c1)); assertFalse(m_scheduler.isRunning(c2)); - - // the next run should complete the group - m_scheduler.run(); assertFalse(m_scheduler.isRunning(parallel)); // and final counts should be 5 and 10 diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java index a732f05e362..31391f1ac4e 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java @@ -8,14 +8,12 @@ import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertThrows; import static org.junit.jupiter.api.Assertions.assertTrue; -import static org.junit.jupiter.api.Assertions.fail; import java.util.ArrayList; import org.junit.jupiter.api.Test; class SchedulerErrorHandlingTests extends CommandTestBase { @Test - @SuppressWarnings("PMD.AvoidCatchingGenericException") void errorDetection() { var mechanism = new Mechanism("X", m_scheduler); @@ -29,23 +27,17 @@ void errorDetection() { new Trigger(m_scheduler, () -> true).onTrue(command); - try { - m_scheduler.run(); - fail("An exception should have been thrown"); - } catch (RuntimeException e) { - assertEquals("The exception", e.getMessage()); + var e = assertThrows(RuntimeException.class, m_scheduler::run); + assertEquals("The exception", e.getMessage()); - assertEquals( - "org.wpilib.commands3.SchedulerErrorHandlingTests", e.getStackTrace()[0].getClassName()); - assertEquals("lambda$errorDetection$0", e.getStackTrace()[0].getMethodName()); + assertEquals( + "org.wpilib.commands3.SchedulerErrorHandlingTests", e.getStackTrace()[0].getClassName()); + assertEquals("lambda$errorDetection$0", e.getStackTrace()[0].getMethodName()); - assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); + assertEquals("=== Command Binding Trace ===", e.getStackTrace()[2].getClassName()); - assertEquals(getClass().getName(), e.getStackTrace()[3].getClassName()); - assertEquals("errorDetection", e.getStackTrace()[3].getMethodName()); - } catch (Throwable t) { - fail("Expected a RuntimeException to be thrown, but got " + t); - } + assertEquals(getClass().getName(), e.getStackTrace()[3].getClassName()); + assertEquals("errorDetection", e.getStackTrace()[3].getMethodName()); } @Test @@ -80,32 +72,26 @@ void nestedErrorDetection() { // The second run will fire the trigger and cause the inner command to run and throw m_scheduler.run(); - try { - m_scheduler.run(); - fail("Index OOB exception expected"); - } catch (IndexOutOfBoundsException e) { - StackTraceElement[] stackTrace = e.getStackTrace(); - - assertEquals("Index -1 out of bounds for length 0", e.getMessage()); - int nestedIndex = 0; - for (; nestedIndex < stackTrace.length; nestedIndex++) { - if (stackTrace[nestedIndex].getClassName().equals(getClass().getName())) { - break; - } - } + var e = assertThrows(IndexOutOfBoundsException.class, m_scheduler::run); + StackTraceElement[] stackTrace = e.getStackTrace(); - // user code trace for the scheduler run invocation (to `scheduler.run()` in the try block) - assertEquals("lambda$nestedErrorDetection$3", stackTrace[nestedIndex].getMethodName()); - assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 1].getMethodName()); - - // user code trace for where the command was scheduled (the `.onTrue()` line) - assertEquals("=== Command Binding Trace ===", stackTrace[nestedIndex + 2].getClassName()); - assertEquals("lambda$nestedErrorDetection$4", stackTrace[nestedIndex + 3].getMethodName()); - assertEquals("lambda$nestedErrorDetection$5", stackTrace[nestedIndex + 4].getMethodName()); - assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 5].getMethodName()); - } catch (Throwable unexpected) { - fail("Expected an IndexOutOfBoundsException to have been thrown, but got" + unexpected); + assertEquals("Index -1 out of bounds for length 0", e.getMessage()); + int nestedIndex = 0; + for (; nestedIndex < stackTrace.length; nestedIndex++) { + if (stackTrace[nestedIndex].getClassName().equals(getClass().getName())) { + break; + } } + + // user code trace for the scheduler run invocation (to `scheduler.run()` in the try block) + assertEquals("lambda$nestedErrorDetection$3", stackTrace[nestedIndex].getMethodName()); + assertEquals("assertThrows", stackTrace[nestedIndex + 1].getMethodName()); + + // user code trace for where the command was scheduled (the `.onTrue()` line) + assertEquals("=== Command Binding Trace ===", stackTrace[nestedIndex + 2].getClassName()); + assertEquals("lambda$nestedErrorDetection$4", stackTrace[nestedIndex + 3].getMethodName()); + assertEquals("lambda$nestedErrorDetection$5", stackTrace[nestedIndex + 4].getMethodName()); + assertEquals("nestedErrorDetection", stackTrace[nestedIndex + 5].getMethodName()); } @Test From d4d3c64928abea95e6260118899f3b5217455a82 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:22:41 -0400 Subject: [PATCH 131/153] Document cancellation event order --- .../src/main/java/org/wpilib/commands3/SchedulerEvent.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java index 0b64c7721b8..32641722bbb 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SchedulerEvent.java @@ -67,7 +67,9 @@ record CompletedWithError(Command command, Throwable error, long timestampMicros implements SchedulerEvent {} /** - * An event marking when a command was canceled. + * An event marking when a command was canceled. If the command was canceled because it was + * interrupted by another command, an {@link Interrupted} will be emitted immediately prior to the + * cancellation event. * * @param command The command that was canceled * @param timestampMicros When the command was canceled From b9593ba5de6a4c5126d8df27b0db36ba808862d4 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:25:05 -0400 Subject: [PATCH 132/153] Minor cleanup for PMD --- .../java/org/wpilib/commands3/SchedulerErrorHandlingTests.java | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java index 31391f1ac4e..758639dc420 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java @@ -56,8 +56,7 @@ void nestedErrorDetection() { .executing( c3 -> { // Throws IndexOutOfBoundsException - var obj = new ArrayList<>(0).get(-1); - System.out.println(obj); // not reached + var unused = new ArrayList<>(0).get(-1); }) .named("Throws IndexOutOfBounds")); c2.park(); From d8f7dad5f05446a1a2b2b3d6e1cb4471202e290c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:36:04 -0400 Subject: [PATCH 133/153] Document scheduler and event loop on controller trigger factories --- .../generate/main/java/commandhid.java.jinja | 19 ++++-- .../button/CommandPS4Controller.java | 62 ++++++++++++----- .../button/CommandPS5Controller.java | 62 ++++++++++++----- .../button/CommandStadiaController.java | 66 ++++++++++++++----- .../button/CommandXboxController.java | 64 +++++++++++++----- 5 files changed, 200 insertions(+), 73 deletions(-) diff --git a/commandsv3/src/generate/main/java/commandhid.java.jinja b/commandsv3/src/generate/main/java/commandhid.java.jinja index 3ec45e4b2aa..17f538a7625 100644 --- a/commandsv3/src/generate/main/java/commandhid.java.jinja +++ b/commandsv3/src/generate/main/java/commandhid.java.jinja @@ -23,7 +23,8 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { private final {{ ConsoleName }}Controller m_hid; /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the {@link Scheduler#getDefault() default scheduler} using its default event loop. * * @param port The port index on the Driver Station that the controller is plugged into. */ @@ -33,7 +34,8 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { } /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the given scheduler using its default event loop. * * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the controller is plugged into. @@ -57,7 +59,9 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { * Constructs a Trigger instance around the {{ button.DocName|default(button.name) }} button's digital signal. * * @return a Trigger instance representing the {{ button.DocName|default(button.name) }} button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #{{ button.name }}(EventLoop) */ public Trigger {{ button.name }}() { @@ -98,8 +102,9 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value * should be in the range [0, 1] where 0 is the unpressed state of the axis. * @return a Trigger instance that is true when the {{ trigger.DocName }}'s axis exceeds the provided - * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler - * button loop}. + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler event + * loop} on the scheduler passed to the controller's constructor, or the {@link + * Scheduler#getDefault default scheduler} if a scheduler was not explicitly provided. */ public Trigger {{ trigger.name }}(double threshold) { return {{ trigger.name }}(threshold, getScheduler().getDefaultEventLoop()); @@ -110,7 +115,9 @@ public class Command{{ ConsoleName }}Controller extends CommandGenericHID { * will be true when the axis value is greater than 0.5. * * @return a Trigger instance that is true when the {{ trigger.DocName }}'s axis exceeds 0.5, attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. */ public Trigger {{ trigger.name }}() { return {{ trigger.name }}(0.5); diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java index 1e7f15f2ea2..e48b2358e08 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS4Controller.java @@ -21,7 +21,8 @@ public class CommandPS4Controller extends CommandGenericHID { private final PS4Controller m_hid; /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the {@link Scheduler#getDefault() default scheduler} using its default event loop. * * @param port The port index on the Driver Station that the controller is plugged into. */ @@ -31,7 +32,8 @@ public CommandPS4Controller(int port) { } /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the given scheduler using its default event loop. * * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the controller is plugged into. @@ -55,7 +57,9 @@ public PS4Controller getHID() { * Constructs a Trigger instance around the square button's digital signal. * * @return a Trigger instance representing the square button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #square(EventLoop) */ public Trigger square() { @@ -77,7 +81,9 @@ public Trigger square(EventLoop loop) { * Constructs a Trigger instance around the cross button's digital signal. * * @return a Trigger instance representing the cross button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #cross(EventLoop) */ public Trigger cross() { @@ -99,7 +105,9 @@ public Trigger cross(EventLoop loop) { * Constructs a Trigger instance around the circle button's digital signal. * * @return a Trigger instance representing the circle button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #circle(EventLoop) */ public Trigger circle() { @@ -121,7 +129,9 @@ public Trigger circle(EventLoop loop) { * Constructs a Trigger instance around the triangle button's digital signal. * * @return a Trigger instance representing the triangle button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #triangle(EventLoop) */ public Trigger triangle() { @@ -143,7 +153,9 @@ public Trigger triangle(EventLoop loop) { * Constructs a Trigger instance around the left trigger 1 button's digital signal. * * @return a Trigger instance representing the left trigger 1 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L1(EventLoop) */ public Trigger L1() { @@ -165,7 +177,9 @@ public Trigger L1(EventLoop loop) { * Constructs a Trigger instance around the right trigger 1 button's digital signal. * * @return a Trigger instance representing the right trigger 1 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R1(EventLoop) */ public Trigger R1() { @@ -187,7 +201,9 @@ public Trigger R1(EventLoop loop) { * Constructs a Trigger instance around the left trigger 2 button's digital signal. * * @return a Trigger instance representing the left trigger 2 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L2(EventLoop) */ public Trigger L2() { @@ -209,7 +225,9 @@ public Trigger L2(EventLoop loop) { * Constructs a Trigger instance around the right trigger 2 button's digital signal. * * @return a Trigger instance representing the right trigger 2 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R2(EventLoop) */ public Trigger R2() { @@ -231,7 +249,9 @@ public Trigger R2(EventLoop loop) { * Constructs a Trigger instance around the share button's digital signal. * * @return a Trigger instance representing the share button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #share(EventLoop) */ public Trigger share() { @@ -253,7 +273,9 @@ public Trigger share(EventLoop loop) { * Constructs a Trigger instance around the options button's digital signal. * * @return a Trigger instance representing the options button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #options(EventLoop) */ public Trigger options() { @@ -275,7 +297,9 @@ public Trigger options(EventLoop loop) { * Constructs a Trigger instance around the L3 (left stick) button's digital signal. * * @return a Trigger instance representing the L3 (left stick) button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L3(EventLoop) */ public Trigger L3() { @@ -297,7 +321,9 @@ public Trigger L3(EventLoop loop) { * Constructs a Trigger instance around the R3 (right stick) button's digital signal. * * @return a Trigger instance representing the R3 (right stick) button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R3(EventLoop) */ public Trigger R3() { @@ -319,7 +345,9 @@ public Trigger R3(EventLoop loop) { * Constructs a Trigger instance around the PlayStation button's digital signal. * * @return a Trigger instance representing the PlayStation button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #PS(EventLoop) */ public Trigger PS() { @@ -341,7 +369,9 @@ public Trigger PS(EventLoop loop) { * Constructs a Trigger instance around the touchpad button's digital signal. * * @return a Trigger instance representing the touchpad button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #touchpad(EventLoop) */ public Trigger touchpad() { diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java index 92f5ef4fba2..5ee032fdb44 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandPS5Controller.java @@ -21,7 +21,8 @@ public class CommandPS5Controller extends CommandGenericHID { private final PS5Controller m_hid; /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the {@link Scheduler#getDefault() default scheduler} using its default event loop. * * @param port The port index on the Driver Station that the controller is plugged into. */ @@ -31,7 +32,8 @@ public CommandPS5Controller(int port) { } /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the given scheduler using its default event loop. * * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the controller is plugged into. @@ -55,7 +57,9 @@ public PS5Controller getHID() { * Constructs a Trigger instance around the square button's digital signal. * * @return a Trigger instance representing the square button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #square(EventLoop) */ public Trigger square() { @@ -77,7 +81,9 @@ public Trigger square(EventLoop loop) { * Constructs a Trigger instance around the cross button's digital signal. * * @return a Trigger instance representing the cross button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #cross(EventLoop) */ public Trigger cross() { @@ -99,7 +105,9 @@ public Trigger cross(EventLoop loop) { * Constructs a Trigger instance around the circle button's digital signal. * * @return a Trigger instance representing the circle button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #circle(EventLoop) */ public Trigger circle() { @@ -121,7 +129,9 @@ public Trigger circle(EventLoop loop) { * Constructs a Trigger instance around the triangle button's digital signal. * * @return a Trigger instance representing the triangle button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #triangle(EventLoop) */ public Trigger triangle() { @@ -143,7 +153,9 @@ public Trigger triangle(EventLoop loop) { * Constructs a Trigger instance around the left trigger 1 button's digital signal. * * @return a Trigger instance representing the left trigger 1 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L1(EventLoop) */ public Trigger L1() { @@ -165,7 +177,9 @@ public Trigger L1(EventLoop loop) { * Constructs a Trigger instance around the right trigger 1 button's digital signal. * * @return a Trigger instance representing the right trigger 1 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R1(EventLoop) */ public Trigger R1() { @@ -187,7 +201,9 @@ public Trigger R1(EventLoop loop) { * Constructs a Trigger instance around the left trigger 2 button's digital signal. * * @return a Trigger instance representing the left trigger 2 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L2(EventLoop) */ public Trigger L2() { @@ -209,7 +225,9 @@ public Trigger L2(EventLoop loop) { * Constructs a Trigger instance around the right trigger 2 button's digital signal. * * @return a Trigger instance representing the right trigger 2 button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R2(EventLoop) */ public Trigger R2() { @@ -231,7 +249,9 @@ public Trigger R2(EventLoop loop) { * Constructs a Trigger instance around the create button's digital signal. * * @return a Trigger instance representing the create button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #create(EventLoop) */ public Trigger create() { @@ -253,7 +273,9 @@ public Trigger create(EventLoop loop) { * Constructs a Trigger instance around the options button's digital signal. * * @return a Trigger instance representing the options button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #options(EventLoop) */ public Trigger options() { @@ -275,7 +297,9 @@ public Trigger options(EventLoop loop) { * Constructs a Trigger instance around the L3 (left stick) button's digital signal. * * @return a Trigger instance representing the L3 (left stick) button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #L3(EventLoop) */ public Trigger L3() { @@ -297,7 +321,9 @@ public Trigger L3(EventLoop loop) { * Constructs a Trigger instance around the R3 (right stick) button's digital signal. * * @return a Trigger instance representing the R3 (right stick) button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #R3(EventLoop) */ public Trigger R3() { @@ -319,7 +345,9 @@ public Trigger R3(EventLoop loop) { * Constructs a Trigger instance around the PlayStation button's digital signal. * * @return a Trigger instance representing the PlayStation button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #PS(EventLoop) */ public Trigger PS() { @@ -341,7 +369,9 @@ public Trigger PS(EventLoop loop) { * Constructs a Trigger instance around the touchpad button's digital signal. * * @return a Trigger instance representing the touchpad button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #touchpad(EventLoop) */ public Trigger touchpad() { diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java index c04ae972994..3b9cdac1c57 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandStadiaController.java @@ -21,7 +21,8 @@ public class CommandStadiaController extends CommandGenericHID { private final StadiaController m_hid; /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the {@link Scheduler#getDefault() default scheduler} using its default event loop. * * @param port The port index on the Driver Station that the controller is plugged into. */ @@ -31,7 +32,8 @@ public CommandStadiaController(int port) { } /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the given scheduler using its default event loop. * * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the controller is plugged into. @@ -55,7 +57,9 @@ public StadiaController getHID() { * Constructs a Trigger instance around the A button's digital signal. * * @return a Trigger instance representing the A button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #a(EventLoop) */ public Trigger a() { @@ -77,7 +81,9 @@ public Trigger a(EventLoop loop) { * Constructs a Trigger instance around the B button's digital signal. * * @return a Trigger instance representing the B button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #b(EventLoop) */ public Trigger b() { @@ -99,7 +105,9 @@ public Trigger b(EventLoop loop) { * Constructs a Trigger instance around the X button's digital signal. * * @return a Trigger instance representing the X button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #x(EventLoop) */ public Trigger x() { @@ -121,7 +129,9 @@ public Trigger x(EventLoop loop) { * Constructs a Trigger instance around the Y button's digital signal. * * @return a Trigger instance representing the Y button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #y(EventLoop) */ public Trigger y() { @@ -143,7 +153,9 @@ public Trigger y(EventLoop loop) { * Constructs a Trigger instance around the left bumper button's digital signal. * * @return a Trigger instance representing the left bumper button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #leftBumper(EventLoop) */ public Trigger leftBumper() { @@ -165,7 +177,9 @@ public Trigger leftBumper(EventLoop loop) { * Constructs a Trigger instance around the right bumper button's digital signal. * * @return a Trigger instance representing the right bumper button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #rightBumper(EventLoop) */ public Trigger rightBumper() { @@ -187,7 +201,9 @@ public Trigger rightBumper(EventLoop loop) { * Constructs a Trigger instance around the left stick button's digital signal. * * @return a Trigger instance representing the left stick button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #leftStick(EventLoop) */ public Trigger leftStick() { @@ -209,7 +225,9 @@ public Trigger leftStick(EventLoop loop) { * Constructs a Trigger instance around the right stick button's digital signal. * * @return a Trigger instance representing the right stick button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #rightStick(EventLoop) */ public Trigger rightStick() { @@ -231,7 +249,9 @@ public Trigger rightStick(EventLoop loop) { * Constructs a Trigger instance around the ellipses button's digital signal. * * @return a Trigger instance representing the ellipses button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #ellipses(EventLoop) */ public Trigger ellipses() { @@ -253,7 +273,9 @@ public Trigger ellipses(EventLoop loop) { * Constructs a Trigger instance around the hamburger button's digital signal. * * @return a Trigger instance representing the hamburger button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #hamburger(EventLoop) */ public Trigger hamburger() { @@ -275,7 +297,9 @@ public Trigger hamburger(EventLoop loop) { * Constructs a Trigger instance around the stadia button's digital signal. * * @return a Trigger instance representing the stadia button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #stadia(EventLoop) */ public Trigger stadia() { @@ -297,7 +321,9 @@ public Trigger stadia(EventLoop loop) { * Constructs a Trigger instance around the right trigger button's digital signal. * * @return a Trigger instance representing the right trigger button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #rightTrigger(EventLoop) */ public Trigger rightTrigger() { @@ -319,7 +345,9 @@ public Trigger rightTrigger(EventLoop loop) { * Constructs a Trigger instance around the left trigger button's digital signal. * * @return a Trigger instance representing the left trigger button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #leftTrigger(EventLoop) */ public Trigger leftTrigger() { @@ -341,7 +369,9 @@ public Trigger leftTrigger(EventLoop loop) { * Constructs a Trigger instance around the google button's digital signal. * * @return a Trigger instance representing the google button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #google(EventLoop) */ public Trigger google() { @@ -363,7 +393,9 @@ public Trigger google(EventLoop loop) { * Constructs a Trigger instance around the frame button's digital signal. * * @return a Trigger instance representing the frame button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #frame(EventLoop) */ public Trigger frame() { diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java index 9ad482df539..ef1008d3961 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/button/CommandXboxController.java @@ -21,7 +21,8 @@ public class CommandXboxController extends CommandGenericHID { private final XboxController m_hid; /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the {@link Scheduler#getDefault() default scheduler} using its default event loop. * * @param port The port index on the Driver Station that the controller is plugged into. */ @@ -31,7 +32,8 @@ public CommandXboxController(int port) { } /** - * Construct an instance of a controller. + * Construct an instance of a controller. Commands bound to buttons on the controller will be + * scheduled on the given scheduler using its default event loop. * * @param scheduler The scheduler that should execute the triggered commands. * @param port The port index on the Driver Station that the controller is plugged into. @@ -55,7 +57,9 @@ public XboxController getHID() { * Constructs a Trigger instance around the A button's digital signal. * * @return a Trigger instance representing the A button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #a(EventLoop) */ public Trigger a() { @@ -77,7 +81,9 @@ public Trigger a(EventLoop loop) { * Constructs a Trigger instance around the B button's digital signal. * * @return a Trigger instance representing the B button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #b(EventLoop) */ public Trigger b() { @@ -99,7 +105,9 @@ public Trigger b(EventLoop loop) { * Constructs a Trigger instance around the X button's digital signal. * * @return a Trigger instance representing the X button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #x(EventLoop) */ public Trigger x() { @@ -121,7 +129,9 @@ public Trigger x(EventLoop loop) { * Constructs a Trigger instance around the Y button's digital signal. * * @return a Trigger instance representing the Y button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #y(EventLoop) */ public Trigger y() { @@ -143,7 +153,9 @@ public Trigger y(EventLoop loop) { * Constructs a Trigger instance around the left bumper button's digital signal. * * @return a Trigger instance representing the left bumper button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #leftBumper(EventLoop) */ public Trigger leftBumper() { @@ -165,7 +177,9 @@ public Trigger leftBumper(EventLoop loop) { * Constructs a Trigger instance around the right bumper button's digital signal. * * @return a Trigger instance representing the right bumper button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #rightBumper(EventLoop) */ public Trigger rightBumper() { @@ -187,7 +201,9 @@ public Trigger rightBumper(EventLoop loop) { * Constructs a Trigger instance around the back button's digital signal. * * @return a Trigger instance representing the back button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #back(EventLoop) */ public Trigger back() { @@ -209,7 +225,9 @@ public Trigger back(EventLoop loop) { * Constructs a Trigger instance around the start button's digital signal. * * @return a Trigger instance representing the start button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #start(EventLoop) */ public Trigger start() { @@ -231,7 +249,9 @@ public Trigger start(EventLoop loop) { * Constructs a Trigger instance around the left stick button's digital signal. * * @return a Trigger instance representing the left stick button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #leftStick(EventLoop) */ public Trigger leftStick() { @@ -253,7 +273,9 @@ public Trigger leftStick(EventLoop loop) { * Constructs a Trigger instance around the right stick button's digital signal. * * @return a Trigger instance representing the right stick button's digital signal attached - * to the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * to the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. * @see #rightStick(EventLoop) */ public Trigger rightStick() { @@ -292,8 +314,9 @@ public Trigger leftTrigger(double threshold, EventLoop loop) { * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value * should be in the range [0, 1] where 0 is the unpressed state of the axis. * @return a Trigger instance that is true when the left trigger's axis exceeds the provided - * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler - * button loop}. + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler event + * loop} on the scheduler passed to the controller's constructor, or the {@link + * Scheduler#getDefault default scheduler} if a scheduler was not explicitly provided. */ public Trigger leftTrigger(double threshold) { return leftTrigger(threshold, getScheduler().getDefaultEventLoop()); @@ -304,7 +327,9 @@ public Trigger leftTrigger(double threshold) { * will be true when the axis value is greater than 0.5. * * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. */ public Trigger leftTrigger() { return leftTrigger(0.5); @@ -331,8 +356,9 @@ public Trigger rightTrigger(double threshold, EventLoop loop) { * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value * should be in the range [0, 1] where 0 is the unpressed state of the axis. * @return a Trigger instance that is true when the right trigger's axis exceeds the provided - * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler - * button loop}. + * threshold, attached to the {@link Scheduler#getDefaultEventLoop() default scheduler event + * loop} on the scheduler passed to the controller's constructor, or the {@link + * Scheduler#getDefault default scheduler} if a scheduler was not explicitly provided. */ public Trigger rightTrigger(double threshold) { return rightTrigger(threshold, getScheduler().getDefaultEventLoop()); @@ -343,7 +369,9 @@ public Trigger rightTrigger(double threshold) { * will be true when the axis value is greater than 0.5. * * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to - * the {@link Scheduler#getDefaultEventLoop() default scheduler button loop}. + * the {@link Scheduler#getDefaultEventLoop() default scheduler event loop} on the + * scheduler passed to the controller's constructor, or the {@link Scheduler#getDefault + * default scheduler} if a scheduler was not explicitly provided. */ public Trigger rightTrigger() { return rightTrigger(0.5); From 42bf6b253ec5b0238d5d2537ee9fde32b8783eae Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:38:29 -0400 Subject: [PATCH 134/153] Rename `forkAll` to `fork` for consistency --- commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java | 2 +- .../src/main/java/org/wpilib/commands3/ParallelGroup.java | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 2dfcb156a67..85c24e8ea4e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -154,7 +154,7 @@ public void fork(Command... commands) { * @param commands The commands to fork. * @throws IllegalStateException if called anywhere other than the coroutine's running command */ - public void forkAll(Collection commands) { + public void fork(Collection commands) { requireMounted(); ConflictDetector.throwIfConflicts(commands); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java index bdb46716212..75025c2b285 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroup.java @@ -71,7 +71,7 @@ public final class ParallelGroup implements Command { @Override public void run(Coroutine coroutine) { - coroutine.forkAll(m_optionalCommands); + coroutine.fork(m_optionalCommands); if (m_requiredCommands.isEmpty()) { // No required commands - just wait for the first optional command to finish From e7cd399da607f825ab12e3b1a6546ac1b0a26199 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:40:28 -0400 Subject: [PATCH 135/153] Covariance --- .../src/main/java/org/wpilib/commands3/Coroutine.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index 85c24e8ea4e..aa505e43cb6 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -154,7 +154,7 @@ public void fork(Command... commands) { * @param commands The commands to fork. * @throws IllegalStateException if called anywhere other than the coroutine's running command */ - public void fork(Collection commands) { + public void fork(Collection commands) { requireMounted(); ConflictDetector.throwIfConflicts(commands); @@ -206,7 +206,7 @@ public void await(Command command) { * @throws IllegalArgumentException if any of the commands conflict with each other * @throws IllegalStateException if called anywhere other than the coroutine's running command */ - public void awaitAll(Collection commands) { + public void awaitAll(Collection commands) { requireMounted(); requireNonNullParam(commands, "commands", "Coroutine.awaitAll"); @@ -247,7 +247,7 @@ public void awaitAll(Command... commands) { * @throws IllegalArgumentException if any of the commands conflict with each other * @throws IllegalStateException if called anywhere other than the coroutine's running command */ - public void awaitAny(Collection commands) { + public void awaitAny(Collection commands) { requireMounted(); requireNonNullParam(commands, "commands", "Coroutine.awaitAny"); From 1893fc01773908a933415dbc5296a9cc8aebe7ec Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 12:51:55 -0400 Subject: [PATCH 136/153] Delegate `fork(Collection)` to variadic overload --- .../java/org/wpilib/commands3/Coroutine.java | 19 +------------------ 1 file changed, 1 insertion(+), 18 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java index aa505e43cb6..71e159e67a5 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Coroutine.java @@ -155,24 +155,7 @@ public void fork(Command... commands) { * @throws IllegalStateException if called anywhere other than the coroutine's running command */ public void fork(Collection commands) { - requireMounted(); - - ConflictDetector.throwIfConflicts(commands); - - requireNonNullParam(commands, "commands", "Coroutine.fork"); - int i = 0; - for (Command command : commands) { - requireNonNullParam(command, "commands[" + i + "]", "Coroutine.fork"); - i++; - } - - // Check for user error; there's no reason to fork conflicting commands simultaneously - ConflictDetector.throwIfConflicts(commands); - - // Shorthand; this is handy for user-defined compositions - for (var command : commands) { - m_scheduler.schedule(command); - } + fork(commands.toArray(Command[]::new)); } /** From 6af662ce5ee68f0f0f21023ac47bedc9f24e262b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 13:03:09 -0400 Subject: [PATCH 137/153] Make scheduler constructor private; use a factory method instead --- .../src/main/java/org/wpilib/commands3/Scheduler.java | 9 +++++++-- .../test/java/org/wpilib/commands3/CommandTestBase.java | 2 +- .../org/wpilib/commands3/StagedCommandBuilderTest.java | 4 ++-- styleguide/spotbugs-exclude.xml | 5 ----- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 8cf9d6697d1..3ee3562cdd9 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -93,7 +93,7 @@ * detect lifecycle events for all commands, including one-shots that would be invisible to the * protobuf serializer. However, it is up to the user to log those events themselves. */ -public class Scheduler implements ProtobufSerializable { +public final class Scheduler implements ProtobufSerializable { private final Map m_defaultCommands = new LinkedHashMap<>(); /** The set of commands scheduled since the start of the previous run. */ @@ -151,7 +151,12 @@ public static Scheduler getDefault() { * default instance for convenience; however, new scheduler instances can be useful for unit * tests. */ - public Scheduler() {} + public static Scheduler createIndependentScheduler() { + return new Scheduler(); + } + + /** Private constructor. Use static factory methods or the default scheduler instance. */ + private Scheduler() {} /** * Sets the default command for a mechanism. The command must require that mechanism, and cannot diff --git a/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java b/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java index 9b278e72826..0423924397a 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/CommandTestBase.java @@ -16,7 +16,7 @@ class CommandTestBase { @BeforeEach void initScheduler() { RobotController.setTimeSource(() -> System.nanoTime() / 1000L); - m_scheduler = new Scheduler(); + m_scheduler = Scheduler.createIndependentScheduler(); m_events = new ArrayList<>(); m_scheduler.addEventListener(m_events::add); } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java index dce01323d30..a7d05458134 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java @@ -23,7 +23,7 @@ class StagedCommandBuilderTest { @BeforeEach void setUp() { - Scheduler scheduler = new Scheduler(); + Scheduler scheduler = Scheduler.createIndependentScheduler(); m_mech1 = new Mechanism("Mech 1", scheduler); m_mech2 = new Mechanism("Mech 2", scheduler); } @@ -44,7 +44,7 @@ void streamlined() { @Test void allOptions() { - var mech = new Mechanism("Mech", new Scheduler()); + var mech = new Mechanism("Mech", Scheduler.createIndependentScheduler()); Command command = new StagedCommandBuilder() diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index b0fb7f01b2b..a2475222f11 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -212,11 +212,6 @@ - - - - - From 97e8941bbbe8a5549fa7262a72729e967df7e96b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 13:12:09 -0400 Subject: [PATCH 138/153] Remove merge artifact --- styleguide/spotbugs-exclude.xml | 8 -------- 1 file changed, 8 deletions(-) diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index a2475222f11..bdebdc55f3e 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -208,12 +208,4 @@ - - - - - - - - From f74fbf89473f5a966f0f338dd7836c02d4024a9b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 13:54:37 -0400 Subject: [PATCH 139/153] Linting --- commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java | 2 ++ .../src/test/java/org/wpilib/commands3/SchedulerTest.java | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 3ee3562cdd9..5514af7231a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -150,6 +150,8 @@ public static Scheduler getDefault() { * they were explicitly constructed with a different scheduler instance. Teams should use the * default instance for convenience; however, new scheduler instances can be useful for unit * tests. + * + * @return a new scheduler instance that is independent of the default scheduler instance. */ public static Scheduler createIndependentScheduler() { return new Scheduler(); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java index 790db18acf4..4d5fd92a7b8 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java @@ -42,7 +42,7 @@ void basic() { } @Test - @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs + @SuppressWarnings("PMD.ImmutableField") // PMD bugs void atomicity() { var mechanism = new Mechanism("X", m_scheduler) { @@ -79,7 +79,7 @@ void atomicity() { } @Test - @SuppressWarnings({"PMD.RedundantFieldInitializer", "PMD.ImmutableField"}) // PMD bugs + @SuppressWarnings("PMD.ImmutableField") // PMD bugs void runMechanism() { var example = new Mechanism("Counting", m_scheduler) { From 8baeb86af2ff017c7712a85a585d20397f175a92 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 14:03:22 -0400 Subject: [PATCH 140/153] Regenerate protobuf classes with script --- .../commands3/proto/ProtobufCommands.java | 105 +++++++++--------- 1 file changed, 54 insertions(+), 51 deletions(-) diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java index e8b69923f02..831e5ab1cec 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java @@ -1,3 +1,6 @@ +// 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. // Code generated by protocol buffer compiler. Do not edit! package org.wpilib.commands3.proto; @@ -17,57 +20,57 @@ import us.hebi.quickbuf.Utf8String; public final class ProtobufCommands { - private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2495, - "CjFjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3Byb3RvYnVmX2NvbW1hbmRzLnByb3RvEgl3cGkucHJv" + - "dG8iJwoRUHJvdG9idWZNZWNoYW5pc20SEgoEbmFtZRgBIAEoCVIEbmFtZSK2AgoPUHJvdG9idWZDb21t" + - "YW5kEg4KAmlkGAEgASgNUgJpZBIgCglwYXJlbnRfaWQYAiABKA1IAFIIcGFyZW50SWSIAQESEgoEbmFt" + - "ZRgDIAEoCVIEbmFtZRIaCghwcmlvcml0eRgEIAEoBVIIcHJpb3JpdHkSQAoMcmVxdWlyZW1lbnRzGAUg" + - "AygLMhwud3BpLnByb3RvLlByb3RvYnVmTWVjaGFuaXNtUgxyZXF1aXJlbWVudHMSJQoMbGFzdF90aW1l" + - "X21zGAYgASgBSAFSCmxhc3RUaW1lTXOIAQESJwoNdG90YWxfdGltZV9tcxgHIAEoAUgCUgt0b3RhbFRp" + - "bWVNc4gBAUIMCgpfcGFyZW50X2lkQg8KDV9sYXN0X3RpbWVfbXNCEAoOX3RvdGFsX3RpbWVfbXMiwQEK" + - "EVByb3RvYnVmU2NoZWR1bGVyEkMKD3F1ZXVlZF9jb21tYW5kcxgBIAMoCzIaLndwaS5wcm90by5Qcm90" + - "b2J1ZkNvbW1hbmRSDnF1ZXVlZENvbW1hbmRzEkUKEHJ1bm5pbmdfY29tbWFuZHMYAiADKAsyGi53cGku" + - "cHJvdG8uUHJvdG9idWZDb21tYW5kUg9ydW5uaW5nQ29tbWFuZHMSIAoMbGFzdF90aW1lX21zGAMgASgB" + - "UgpsYXN0VGltZU1zQhwKGm9yZy53cGlsaWIuY29tbWFuZHMzLnByb3RvSrIOCgYSBAAANAEKCAoBDBID" + - "AAASCggKAQISAwIAEgoICgEIEgMEADMKCQoCCAESAwQAMwqnAQoCBAASBAwADgEymgEKYWxsd3BpbGli" + - "ICQgcHJvdG9jLXF1aWNrYnVmIFwKLS1xdWlja2J1Zl9vdXQ9Z2VuX2Rlc2NyaXB0b3JzPXRydWU6Y29t" + - "bWFuZHN2My9zcmMvZ2VuZXJhdGVkL21haW4vamF2YSBcCmNvbW1hbmRzdjMvc3JjL21haW4vcHJvdG8v" + - "cHJvdG9idWZfY29tbWFuZHMucHJvdG8KCgoKAwQAARIDDAgZCgsKBAQAAgASAw0CEgoMCgUEAAIABRID" + - "DQIICgwKBQQAAgABEgMNCQ0KDAoFBAACAAMSAw0QEQoKCgIEARIEEAApAQoKCgMEAQESAxAIFwpxCgQE" + - "AQIAEgMTAhAaZCBBIHVuaXF1ZSBJRCBmb3IgdGhlIGNvbW1hbmQuCiBEaWZmZXJlbnQgaW52b2NhdGlv" + - "bnMgb2YgdGhlIHNhbWUgY29tbWFuZCBvYmplY3QgaGF2ZSBkaWZmZXJlbnQgSURzLgoKDAoFBAECAAUS" + - "AxMCCAoMCgUEAQIAARIDEwkLCgwKBQQBAgADEgMTDg8KYQoEBAECARIDFwIgGlQgVGhlIElEIG9mIHRo" + - "ZSBwYXJlbnQgY29tbWFuZC4KIE5vdCBpbmNsdWRlZCBpbiB0aGUgbWVzc2FnZSBmb3IgdG9wLWxldmVs", - "IGNvbW1hbmRzLgoKDAoFBAECAQQSAxcCCgoMCgUEAQIBBRIDFwsRCgwKBQQBAgEBEgMXEhsKDAoFBAEC" + - "AQMSAxceHwonCgQEAQICEgMaAhIaGiBUaGUgbmFtZSBvZiB0aGUgY29tbWFuZC4KCgwKBQQBAgIFEgMa" + - "AggKDAoFBAECAgESAxoJDQoMCgUEAQICAxIDGhARCjEKBAQBAgMSAx0CFRokIFRoZSBwcmlvcml0eSBs" + - "ZXZlbCBvZiB0aGUgY29tbWFuZC4KCgwKBQQBAgMFEgMdAgcKDAoFBAECAwESAx0IEAoMCgUEAQIDAxID" + - "HRMUCjYKBAQBAgQSAyACLhopIFRoZSBtZWNoYW5pc21zIHJlcXVpcmVkIGJ5IHRoZSBjb21tYW5kLgoK" + - "DAoFBAECBAQSAyACCgoMCgUEAQIEBhIDIAscCgwKBQQBAgQBEgMgHSkKDAoFBAECBAMSAyAsLQqOAQoE" + - "BAECBRIDJAIjGoABIEhvdyBtdWNoIHRpbWUgdGhlIGNvbW1hbmQgdG9vayB0byBleGVjdXRlIGluIGl0" + - "cyBtb3N0IHJlY2VudCBydW4uCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZl" + - "bHkgcnVubmluZyBjb21tYW5kLgoKDAoFBAECBQQSAyQCCgoMCgUEAQIFBRIDJAsRCgwKBQQBAgUBEgMk" + - "Eh4KDAoFBAECBQMSAyQhIgqAAQoEBAECBhIDKAIkGnMgSG93IGxvbmcgdGhlIGNvbW1hbmQgaGFzIHRh" + - "a2VuIHRvIHJ1biwgaW4gYWdncmVnYXRlLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFu" + - "IGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQBAgYEEgMoAgoKDAoFBAECBgUSAygLEQoMCgUE" + - "AQIGARIDKBIfCgwKBQQBAgYDEgMoIiMKCgoCBAISBCsANAEKCgoDBAIBEgMrCBkKjQIKBAQCAgASAy8C" + - "Lxr/ASBOb3RlOiBjb21tYW5kcyBhcmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2gg" + - "b2NjdXJzIGltbWVkaWF0ZWx5IGJlZm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5p" + - "bmcuIEVudHJpZXMgd2lsbCBvbmx5IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVs" + - "ZXIKIF9hZnRlcl8gbWFudWFsbHkgc2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxp" + - "bmcgc2NoZWR1bGVyLnJ1bigpCgoMCgUEAgIABBIDLwIKCgwKBQQCAgAGEgMvCxoKDAoFBAICAAESAy8b" + - "KgoMCgUEAgIAAxIDLy0uCgsKBAQCAgESAzACMAoMCgUEAgIBBBIDMAIKCgwKBQQCAgEGEgMwCxoKDAoF" + - "BAICAQESAzAbKwoMCgUEAgIBAxIDMC4vCk8KBAQCAgISAzMCGhpCIEhvdyBtdWNoIHRpbWUgdGhlIHNj", - "aGVkdWxlciB0b29rIGluIGl0cyBsYXN0IGBydW4oKWAgaW52b2NhdGlvbi4KCgwKBQQCAgIFEgMzAggK" + - "DAoFBAICAgESAzMJFQoMCgUEAgICAxIDMxgZYgZwcm90bzM="); - - static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("commandsv3/src/main/proto/protobuf_commands.proto", "wpi.proto", descriptorData); - - static final Descriptors.Descriptor wpi_proto_ProtobufMechanism_descriptor = descriptor.internalContainedType(64, 39, "ProtobufMechanism", "wpi.proto.ProtobufMechanism"); - - static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(106, 310, "ProtobufCommand", "wpi.proto.ProtobufCommand"); - - static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(419, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2469, + "Chdwcm90b2J1Zl9jb21tYW5kcy5wcm90bxIJd3BpLnByb3RvIicKEVByb3RvYnVmTWVjaGFuaXNtEhIK" + + "BG5hbWUYASABKAlSBG5hbWUitgIKD1Byb3RvYnVmQ29tbWFuZBIOCgJpZBgBIAEoDVICaWQSIAoJcGFy" + + "ZW50X2lkGAIgASgNSABSCHBhcmVudElkiAEBEhIKBG5hbWUYAyABKAlSBG5hbWUSGgoIcHJpb3JpdHkY" + + "BCABKAVSCHByaW9yaXR5EkAKDHJlcXVpcmVtZW50cxgFIAMoCzIcLndwaS5wcm90by5Qcm90b2J1Zk1l" + + "Y2hhbmlzbVIMcmVxdWlyZW1lbnRzEiUKDGxhc3RfdGltZV9tcxgGIAEoAUgBUgpsYXN0VGltZU1ziAEB" + + "EicKDXRvdGFsX3RpbWVfbXMYByABKAFIAlILdG90YWxUaW1lTXOIAQFCDAoKX3BhcmVudF9pZEIPCg1f" + + "bGFzdF90aW1lX21zQhAKDl90b3RhbF90aW1lX21zIsEBChFQcm90b2J1ZlNjaGVkdWxlchJDCg9xdWV1" + + "ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg5xdWV1ZWRDb21tYW5k" + + "cxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnByb3RvLlByb3RvYnVmQ29tbWFuZFIPcnVu" + + "bmluZ0NvbW1hbmRzEiAKDGxhc3RfdGltZV9tcxgDIAEoAVIKbGFzdFRpbWVNc0IcChpvcmcud3BpbGli" + + "LmNvbW1hbmRzMy5wcm90b0qyDgoGEgQAADQBCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAzCgkK" + + "AggBEgMEADMKpwEKAgQAEgQMAA4BMpoBCmFsbHdwaWxpYiAkIHByb3RvYy1xdWlja2J1ZiBcCi0tcXVp" + + "Y2tidWZfb3V0PWdlbl9kZXNjcmlwdG9ycz10cnVlOmNvbW1hbmRzdjMvc3JjL2dlbmVyYXRlZC9tYWlu" + + "L2phdmEgXApjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3Byb3RvYnVmX2NvbW1hbmRzLnByb3RvCgoK" + + "CgMEAAESAwwIGQoLCgQEAAIAEgMNAhIKDAoFBAACAAUSAw0CCAoMCgUEAAIAARIDDQkNCgwKBQQAAgAD" + + "EgMNEBEKCgoCBAESBBAAKQEKCgoDBAEBEgMQCBcKcQoEBAECABIDEwIQGmQgQSB1bmlxdWUgSUQgZm9y" + + "IHRoZSBjb21tYW5kLgogRGlmZmVyZW50IGludm9jYXRpb25zIG9mIHRoZSBzYW1lIGNvbW1hbmQgb2Jq" + + "ZWN0IGhhdmUgZGlmZmVyZW50IElEcy4KCgwKBQQBAgAFEgMTAggKDAoFBAECAAESAxMJCwoMCgUEAQIA" + + "AxIDEw4PCmEKBAQBAgESAxcCIBpUIFRoZSBJRCBvZiB0aGUgcGFyZW50IGNvbW1hbmQuCiBOb3QgaW5j" + + "bHVkZWQgaW4gdGhlIG1lc3NhZ2UgZm9yIHRvcC1sZXZlbCBjb21tYW5kcy4KCgwKBQQBAgEEEgMXAgoK", + "DAoFBAECAQUSAxcLEQoMCgUEAQIBARIDFxIbCgwKBQQBAgEDEgMXHh8KJwoEBAECAhIDGgISGhogVGhl" + + "IG5hbWUgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQICBRIDGgIICgwKBQQBAgIBEgMaCQ0KDAoFBAECAgMS" + + "AxoQEQoxCgQEAQIDEgMdAhUaJCBUaGUgcHJpb3JpdHkgbGV2ZWwgb2YgdGhlIGNvbW1hbmQuCgoMCgUE" + + "AQIDBRIDHQIHCgwKBQQBAgMBEgMdCBAKDAoFBAECAwMSAx0TFAo2CgQEAQIEEgMgAi4aKSBUaGUgbWVj" + + "aGFuaXNtcyByZXF1aXJlZCBieSB0aGUgY29tbWFuZC4KCgwKBQQBAgQEEgMgAgoKDAoFBAECBAYSAyAL" + + "HAoMCgUEAQIEARIDIB0pCgwKBQQBAgQDEgMgLC0KjgEKBAQBAgUSAyQCIxqAASBIb3cgbXVjaCB0aW1l" + + "IHRoZSBjb21tYW5kIHRvb2sgdG8gZXhlY3V0ZSBpbiBpdHMgbW9zdCByZWNlbnQgcnVuLgogT25seSBp" + + "bmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFuIGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQB" + + "AgUEEgMkAgoKDAoFBAECBQUSAyQLEQoMCgUEAQIFARIDJBIeCgwKBQQBAgUDEgMkISIKgAEKBAQBAgYS" + + "AygCJBpzIEhvdyBsb25nIHRoZSBjb21tYW5kIGhhcyB0YWtlbiB0byBydW4sIGluIGFnZ3JlZ2F0ZS4K" + + "IE9ubHkgaW5jbHVkZWQgaW4gYSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQu" + + "CgoMCgUEAQIGBBIDKAIKCgwKBQQBAgYFEgMoCxEKDAoFBAECBgESAygSHwoMCgUEAQIGAxIDKCIjCgoK" + + "AgQCEgQrADQBCgoKAwQCARIDKwgZCo0CCgQEAgIAEgMvAi8a/wEgTm90ZTogY29tbWFuZHMgYXJlIGdl" + + "bmVyYWxseSBxdWV1ZWQgYnkgdHJpZ2dlcnMsIHdoaWNoIG9jY3VycyBpbW1lZGlhdGVseSBiZWZvcmUg" + + "dGhleSBhcmUKIHByb21vdGVkIGFuZCBzdGFydCBydW5uaW5nLiBFbnRyaWVzIHdpbGwgb25seSBhcHBl" + + "YXIgaGVyZSB3aGVuIHNlcmlhbGl6aW5nIGEgc2NoZWR1bGVyCiBfYWZ0ZXJfIG1hbnVhbGx5IHNjaGVk" + + "dWxpbmcgYSBjb21tYW5kIGJ1dCBfYmVmb3JlXyBjYWxsaW5nIHNjaGVkdWxlci5ydW4oKQoKDAoFBAIC" + + "AAQSAy8CCgoMCgUEAgIABhIDLwsaCgwKBQQCAgABEgMvGyoKDAoFBAICAAMSAy8tLgoLCgQEAgIBEgMw" + + "AjAKDAoFBAICAQQSAzACCgoMCgUEAgIBBhIDMAsaCgwKBQQCAgEBEgMwGysKDAoFBAICAQMSAzAuLwpP" + + "CgQEAgICEgMzAhoaQiBIb3cgbXVjaCB0aW1lIHRoZSBzY2hlZHVsZXIgdG9vayBpbiBpdHMgbGFzdCBg", + "cnVuKClgIGludm9jYXRpb24uCgoMCgUEAgICBRIDMwIICgwKBQQCAgIBEgMzCRUKDAoFBAICAgMSAzMY" + + "GWIGcHJvdG8z"); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("protobuf_commands.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufMechanism_descriptor = descriptor.internalContainedType(38, 39, "ProtobufMechanism", "wpi.proto.ProtobufMechanism"); + + static final Descriptors.Descriptor wpi_proto_ProtobufCommand_descriptor = descriptor.internalContainedType(80, 310, "ProtobufCommand", "wpi.proto.ProtobufCommand"); + + static final Descriptors.Descriptor wpi_proto_ProtobufScheduler_descriptor = descriptor.internalContainedType(393, 193, "ProtobufScheduler", "wpi.proto.ProtobufScheduler"); /** * @return this proto file's descriptor. From 5a62bff96170b3932700322fa2f02ecae812144c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 14:04:27 -0400 Subject: [PATCH 141/153] Update generate_files to work on macOS without modifications --- commandsv3/generate_files.py | 20 +++++++++---------- .../src/main/proto/protobuf_commands.proto | 10 +++++++--- 2 files changed, 17 insertions(+), 13 deletions(-) diff --git a/commandsv3/generate_files.py b/commandsv3/generate_files.py index d2b35322c7c..f6c1cb20c00 100755 --- a/commandsv3/generate_files.py +++ b/commandsv3/generate_files.py @@ -44,15 +44,16 @@ def generate_quickbuf( proto_files = proto_dir.glob("*.proto") for path in proto_files: absolute_filename = path.absolute() - subprocess.check_call( - [ - protoc, - f"--plugin=protoc-gen-quickbuf={quickbuf_plugin}", - f"--quickbuf_out=gen_descriptors=true:{output_directory.absolute()}", - f"-I{absolute_filename.parent}", - absolute_filename, - ] - ) + args = [protoc] + if quickbuf_plugin: + # Optional on macOS if using protoc-quickbuf + args += [f"--plugin=protoc-gen-quickbuf={quickbuf_plugin}"] + args += [ + f"--quickbuf_out=gen_descriptors=true:{output_directory.absolute()}", + f"-I{absolute_filename.parent}", + absolute_filename, + ] + subprocess.check_call(args) java_files = (output_directory / "org/wpilib/commands3/proto").glob("*.java") for java_file in java_files: with (java_file).open(encoding="utf-8") as f: @@ -97,7 +98,6 @@ def main(): parser.add_argument( "--quickbuf_plugin", help="Path to the quickbuf protoc plugin", - required=True, ) parser.add_argument( "--proto_directory", diff --git a/commandsv3/src/main/proto/protobuf_commands.proto b/commandsv3/src/main/proto/protobuf_commands.proto index a23cf90ce4d..beaba6b8c0d 100644 --- a/commandsv3/src/main/proto/protobuf_commands.proto +++ b/commandsv3/src/main/proto/protobuf_commands.proto @@ -5,9 +5,13 @@ package wpi.proto; option java_package = "org.wpilib.commands3.proto"; /* -allwpilib $ protoc-quickbuf \ - --quickbuf_out=gen_descriptors=true:commandsv3/src/generated/main/java \ - commandsv3/src/main/proto/protobuf_commands.proto +Or use the generate_files.py script: + +# macOS +allwpilib $ ./commandsv3/generate_files.py --protoc=protoc-quickbuf + +# Linux +allwpilib $ ./commandsv3/generate_files.py --quickbuf_plugin protoc-gen-quickbuf-1.3.3-linux-x86_64.exe */ message ProtobufMechanism { From 3abcf09aa5b34f0f06f2a2d60b0885e6ddba44ce Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 14:04:50 -0400 Subject: [PATCH 142/153] Update default command documentation --- commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index f7e9831a0aa..2ef1a6fd705 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -69,8 +69,8 @@ public String getName() { * Sets the default command to run on the mechanism when no other command is scheduled. The * default command's priority is effectively the minimum allowable priority for any command * requiring a mechanism. For this reason, it's recommended that a default command have a priority - * less than{@link Command#DEFAULT_PRIORITY} to prevent it from blocking other, non-default - * commands from running. + * less than {@link Command#DEFAULT_PRIORITY} so it doesn't prevent low-priority commands from + * running. * *

    The default command is initially an idle command that only owns the mechanism without doing * anything. This command has the lowest possible priority to allow any other command to run. From 15760f20fa33662340f2c2b37be5c70a8e70397e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 14:07:49 -0400 Subject: [PATCH 143/153] Regenerate protbuf classes ??? --- .../commands3/proto/ProtobufCommands.java | 67 ++++++++++--------- 1 file changed, 34 insertions(+), 33 deletions(-) diff --git a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java index 831e5ab1cec..d0b91ff4767 100644 --- a/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java +++ b/commandsv3/src/generated/main/java/org/wpilib/commands3/proto/ProtobufCommands.java @@ -20,7 +20,7 @@ import us.hebi.quickbuf.Utf8String; public final class ProtobufCommands { - private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2469, + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(2543, "Chdwcm90b2J1Zl9jb21tYW5kcy5wcm90bxIJd3BpLnByb3RvIicKEVByb3RvYnVmTWVjaGFuaXNtEhIK" + "BG5hbWUYASABKAlSBG5hbWUitgIKD1Byb3RvYnVmQ29tbWFuZBIOCgJpZBgBIAEoDVICaWQSIAoJcGFy" + "ZW50X2lkGAIgASgNSABSCHBhcmVudElkiAEBEhIKBG5hbWUYAyABKAlSBG5hbWUSGgoIcHJpb3JpdHkY" + @@ -31,38 +31,39 @@ public final class ProtobufCommands { "ZWRfY29tbWFuZHMYASADKAsyGi53cGkucHJvdG8uUHJvdG9idWZDb21tYW5kUg5xdWV1ZWRDb21tYW5k" + "cxJFChBydW5uaW5nX2NvbW1hbmRzGAIgAygLMhoud3BpLnByb3RvLlByb3RvYnVmQ29tbWFuZFIPcnVu" + "bmluZ0NvbW1hbmRzEiAKDGxhc3RfdGltZV9tcxgDIAEoAVIKbGFzdFRpbWVNc0IcChpvcmcud3BpbGli" + - "LmNvbW1hbmRzMy5wcm90b0qyDgoGEgQAADQBCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAzCgkK" + - "AggBEgMEADMKpwEKAgQAEgQMAA4BMpoBCmFsbHdwaWxpYiAkIHByb3RvYy1xdWlja2J1ZiBcCi0tcXVp" + - "Y2tidWZfb3V0PWdlbl9kZXNjcmlwdG9ycz10cnVlOmNvbW1hbmRzdjMvc3JjL2dlbmVyYXRlZC9tYWlu" + - "L2phdmEgXApjb21tYW5kc3YzL3NyYy9tYWluL3Byb3RvL3Byb3RvYnVmX2NvbW1hbmRzLnByb3RvCgoK" + - "CgMEAAESAwwIGQoLCgQEAAIAEgMNAhIKDAoFBAACAAUSAw0CCAoMCgUEAAIAARIDDQkNCgwKBQQAAgAD" + - "EgMNEBEKCgoCBAESBBAAKQEKCgoDBAEBEgMQCBcKcQoEBAECABIDEwIQGmQgQSB1bmlxdWUgSUQgZm9y" + - "IHRoZSBjb21tYW5kLgogRGlmZmVyZW50IGludm9jYXRpb25zIG9mIHRoZSBzYW1lIGNvbW1hbmQgb2Jq" + - "ZWN0IGhhdmUgZGlmZmVyZW50IElEcy4KCgwKBQQBAgAFEgMTAggKDAoFBAECAAESAxMJCwoMCgUEAQIA" + - "AxIDEw4PCmEKBAQBAgESAxcCIBpUIFRoZSBJRCBvZiB0aGUgcGFyZW50IGNvbW1hbmQuCiBOb3QgaW5j" + - "bHVkZWQgaW4gdGhlIG1lc3NhZ2UgZm9yIHRvcC1sZXZlbCBjb21tYW5kcy4KCgwKBQQBAgEEEgMXAgoK", - "DAoFBAECAQUSAxcLEQoMCgUEAQIBARIDFxIbCgwKBQQBAgEDEgMXHh8KJwoEBAECAhIDGgISGhogVGhl" + - "IG5hbWUgb2YgdGhlIGNvbW1hbmQuCgoMCgUEAQICBRIDGgIICgwKBQQBAgIBEgMaCQ0KDAoFBAECAgMS" + - "AxoQEQoxCgQEAQIDEgMdAhUaJCBUaGUgcHJpb3JpdHkgbGV2ZWwgb2YgdGhlIGNvbW1hbmQuCgoMCgUE" + - "AQIDBRIDHQIHCgwKBQQBAgMBEgMdCBAKDAoFBAECAwMSAx0TFAo2CgQEAQIEEgMgAi4aKSBUaGUgbWVj" + - "aGFuaXNtcyByZXF1aXJlZCBieSB0aGUgY29tbWFuZC4KCgwKBQQBAgQEEgMgAgoKDAoFBAECBAYSAyAL" + - "HAoMCgUEAQIEARIDIB0pCgwKBQQBAgQDEgMgLC0KjgEKBAQBAgUSAyQCIxqAASBIb3cgbXVjaCB0aW1l" + - "IHRoZSBjb21tYW5kIHRvb2sgdG8gZXhlY3V0ZSBpbiBpdHMgbW9zdCByZWNlbnQgcnVuLgogT25seSBp" + - "bmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFuIGFjdGl2ZWx5IHJ1bm5pbmcgY29tbWFuZC4KCgwKBQQB" + - "AgUEEgMkAgoKDAoFBAECBQUSAyQLEQoMCgUEAQIFARIDJBIeCgwKBQQBAgUDEgMkISIKgAEKBAQBAgYS" + - "AygCJBpzIEhvdyBsb25nIHRoZSBjb21tYW5kIGhhcyB0YWtlbiB0byBydW4sIGluIGFnZ3JlZ2F0ZS4K" + - "IE9ubHkgaW5jbHVkZWQgaW4gYSBtZXNzYWdlIGZvciBhbiBhY3RpdmVseSBydW5uaW5nIGNvbW1hbmQu" + - "CgoMCgUEAQIGBBIDKAIKCgwKBQQBAgYFEgMoCxEKDAoFBAECBgESAygSHwoMCgUEAQIGAxIDKCIjCgoK" + - "AgQCEgQrADQBCgoKAwQCARIDKwgZCo0CCgQEAgIAEgMvAi8a/wEgTm90ZTogY29tbWFuZHMgYXJlIGdl" + - "bmVyYWxseSBxdWV1ZWQgYnkgdHJpZ2dlcnMsIHdoaWNoIG9jY3VycyBpbW1lZGlhdGVseSBiZWZvcmUg" + - "dGhleSBhcmUKIHByb21vdGVkIGFuZCBzdGFydCBydW5uaW5nLiBFbnRyaWVzIHdpbGwgb25seSBhcHBl" + - "YXIgaGVyZSB3aGVuIHNlcmlhbGl6aW5nIGEgc2NoZWR1bGVyCiBfYWZ0ZXJfIG1hbnVhbGx5IHNjaGVk" + - "dWxpbmcgYSBjb21tYW5kIGJ1dCBfYmVmb3JlXyBjYWxsaW5nIHNjaGVkdWxlci5ydW4oKQoKDAoFBAIC" + - "AAQSAy8CCgoMCgUEAgIABhIDLwsaCgwKBQQCAgABEgMvGyoKDAoFBAICAAMSAy8tLgoLCgQEAgIBEgMw" + - "AjAKDAoFBAICAQQSAzACCgoMCgUEAgIBBhIDMAsaCgwKBQQCAgEBEgMwGysKDAoFBAICAQMSAzAuLwpP" + - "CgQEAgICEgMzAhoaQiBIb3cgbXVjaCB0aW1lIHRoZSBzY2hlZHVsZXIgdG9vayBpbiBpdHMgbGFzdCBg", - "cnVuKClgIGludm9jYXRpb24uCgoMCgUEAgICBRIDMwIICgwKBQQCAgIBEgMzCRUKDAoFBAICAgMSAzMY" + - "GWIGcHJvdG8z"); + "LmNvbW1hbmRzMy5wcm90b0r8DgoGEgQAADgBCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAzCgkK" + + "AggBEgMEADMK8QEKAgQAEgQQABIBMuQBCk9yIHVzZSB0aGUgZ2VuZXJhdGVfZmlsZXMucHkgc2NyaXB0" + + "OgoKIyBtYWNPUwphbGx3cGlsaWIgJCAuL2NvbW1hbmRzdjMvZ2VuZXJhdGVfZmlsZXMucHkgLS1wcm90" + + "b2M9cHJvdG9jLXF1aWNrYnVmCgojIExpbnV4CmFsbHdwaWxpYiAkIC4vY29tbWFuZHN2My9nZW5lcmF0" + + "ZV9maWxlcy5weSAtLXF1aWNrYnVmX3BsdWdpbiBwcm90b2MtZ2VuLXF1aWNrYnVmLTEuMy4zLWxpbnV4" + + "LXg4Nl82NC5leGUKCgoKAwQAARIDEAgZCgsKBAQAAgASAxECEgoMCgUEAAIABRIDEQIICgwKBQQAAgAB" + + "EgMRCQ0KDAoFBAACAAMSAxEQEQoKCgIEARIEFAAtAQoKCgMEAQESAxQIFwpxCgQEAQIAEgMXAhAaZCBB" + + "IHVuaXF1ZSBJRCBmb3IgdGhlIGNvbW1hbmQuCiBEaWZmZXJlbnQgaW52b2NhdGlvbnMgb2YgdGhlIHNh" + + "bWUgY29tbWFuZCBvYmplY3QgaGF2ZSBkaWZmZXJlbnQgSURzLgoKDAoFBAECAAUSAxcCCAoMCgUEAQIA" + + "ARIDFwkLCgwKBQQBAgADEgMXDg8KYQoEBAECARIDGwIgGlQgVGhlIElEIG9mIHRoZSBwYXJlbnQgY29t", + "bWFuZC4KIE5vdCBpbmNsdWRlZCBpbiB0aGUgbWVzc2FnZSBmb3IgdG9wLWxldmVsIGNvbW1hbmRzLgoK" + + "DAoFBAECAQQSAxsCCgoMCgUEAQIBBRIDGwsRCgwKBQQBAgEBEgMbEhsKDAoFBAECAQMSAxseHwonCgQE" + + "AQICEgMeAhIaGiBUaGUgbmFtZSBvZiB0aGUgY29tbWFuZC4KCgwKBQQBAgIFEgMeAggKDAoFBAECAgES" + + "Ax4JDQoMCgUEAQICAxIDHhARCjEKBAQBAgMSAyECFRokIFRoZSBwcmlvcml0eSBsZXZlbCBvZiB0aGUg" + + "Y29tbWFuZC4KCgwKBQQBAgMFEgMhAgcKDAoFBAECAwESAyEIEAoMCgUEAQIDAxIDIRMUCjYKBAQBAgQS" + + "AyQCLhopIFRoZSBtZWNoYW5pc21zIHJlcXVpcmVkIGJ5IHRoZSBjb21tYW5kLgoKDAoFBAECBAQSAyQC" + + "CgoMCgUEAQIEBhIDJAscCgwKBQQBAgQBEgMkHSkKDAoFBAECBAMSAyQsLQqOAQoEBAECBRIDKAIjGoAB" + + "IEhvdyBtdWNoIHRpbWUgdGhlIGNvbW1hbmQgdG9vayB0byBleGVjdXRlIGluIGl0cyBtb3N0IHJlY2Vu" + + "dCBydW4uCiBPbmx5IGluY2x1ZGVkIGluIGEgbWVzc2FnZSBmb3IgYW4gYWN0aXZlbHkgcnVubmluZyBj" + + "b21tYW5kLgoKDAoFBAECBQQSAygCCgoMCgUEAQIFBRIDKAsRCgwKBQQBAgUBEgMoEh4KDAoFBAECBQMS" + + "AyghIgqAAQoEBAECBhIDLAIkGnMgSG93IGxvbmcgdGhlIGNvbW1hbmQgaGFzIHRha2VuIHRvIHJ1biwg" + + "aW4gYWdncmVnYXRlLgogT25seSBpbmNsdWRlZCBpbiBhIG1lc3NhZ2UgZm9yIGFuIGFjdGl2ZWx5IHJ1" + + "bm5pbmcgY29tbWFuZC4KCgwKBQQBAgYEEgMsAgoKDAoFBAECBgUSAywLEQoMCgUEAQIGARIDLBIfCgwK" + + "BQQBAgYDEgMsIiMKCgoCBAISBC8AOAEKCgoDBAIBEgMvCBkKjQIKBAQCAgASAzMCLxr/ASBOb3RlOiBj" + + "b21tYW5kcyBhcmUgZ2VuZXJhbGx5IHF1ZXVlZCBieSB0cmlnZ2Vycywgd2hpY2ggb2NjdXJzIGltbWVk" + + "aWF0ZWx5IGJlZm9yZSB0aGV5IGFyZQogcHJvbW90ZWQgYW5kIHN0YXJ0IHJ1bm5pbmcuIEVudHJpZXMg" + + "d2lsbCBvbmx5IGFwcGVhciBoZXJlIHdoZW4gc2VyaWFsaXppbmcgYSBzY2hlZHVsZXIKIF9hZnRlcl8g" + + "bWFudWFsbHkgc2NoZWR1bGluZyBhIGNvbW1hbmQgYnV0IF9iZWZvcmVfIGNhbGxpbmcgc2NoZWR1bGVy" + + "LnJ1bigpCgoMCgUEAgIABBIDMwIKCgwKBQQCAgAGEgMzCxoKDAoFBAICAAESAzMbKgoMCgUEAgIAAxID" + + "My0uCgsKBAQCAgESAzQCMAoMCgUEAgIBBBIDNAIKCgwKBQQCAgEGEgM0CxoKDAoFBAICAQESAzQbKwoM", + "CgUEAgIBAxIDNC4vCk8KBAQCAgISAzcCGhpCIEhvdyBtdWNoIHRpbWUgdGhlIHNjaGVkdWxlciB0b29r" + + "IGluIGl0cyBsYXN0IGBydW4oKWAgaW52b2NhdGlvbi4KCgwKBQQCAgIFEgM3AggKDAoFBAICAgESAzcJ" + + "FQoMCgUEAgICAxIDNxgZYgZwcm90bzM="); static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("protobuf_commands.proto", "wpi.proto", descriptorData); From 5ce3fa17b138bf280e989170c76f9c1580c43b35 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 13 Sep 2025 14:13:41 -0400 Subject: [PATCH 144/153] Remove unnecessary suppression --- commandsv3/src/main/java/org/wpilib/commands3/CommandState.java | 1 - 1 file changed, 1 deletion(-) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java index 5d37182ae32..ab10842f139 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/CommandState.java @@ -9,7 +9,6 @@ /** Represents the state of a command as it is executed by the scheduler. */ final class CommandState { // Two billion unique IDs should be enough for anybody. - @SuppressWarnings("PMD.RedundantFieldInitializer") // we're explicitly counting up from zero private static int s_lastId = 0; private final Command m_command; From d6cae872bc32a4dada3ecf57f804d9559331b42b Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 25 Sep 2025 19:05:32 -0400 Subject: [PATCH 145/153] Test updates --- .../wpilib/commands3/ParallelGroupTest.java | 20 +++++++ .../commands3/SchedulerCancellationTests.java | 13 ++-- .../commands3/SchedulerConflictTests.java | 6 +- .../SchedulerPriorityLevelTests.java | 10 +--- .../commands3/SchedulerTimingTests.java | 59 +++++++++++++++++-- .../wpilib/commands3/SequentialGroupTest.java | 22 +++++++ 6 files changed, 105 insertions(+), 25 deletions(-) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java index 0e711102147..f89bd647f0d 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java @@ -210,4 +210,24 @@ void automaticNameDeadline() { var group = new ParallelGroupBuilder().requiring(a).optional(b, c).withAutomaticName(); assertEquals("[(A) * (B | C)]", group.name()); } + + @Test + void inheritsRequirements() { + var mech1 = new Mechanism("Mech 1", m_scheduler); + var mech2 = new Mechanism("Mech 2", m_scheduler); + var command1 = mech1.run(Coroutine::park).named("Command 1"); + var command2 = mech2.run(Coroutine::park).named("Command 2"); + var group = new ParallelGroup("Group", Set.of(command1, command2), Set.of()); + assertEquals(Set.of(mech1, mech2), group.requirements(), "Requirements were not inherited"); + } + + @Test + void inheritsPriority() { + var mech1 = new Mechanism("Mech 1", m_scheduler); + var mech2 = new Mechanism("Mech 2", m_scheduler); + var command1 = mech1.run(Coroutine::park).withPriority(100).named("Command 1"); + var command2 = mech2.run(Coroutine::park).withPriority(200).named("Command 2"); + var group = new ParallelGroup("Group", Set.of(command1, command2), Set.of()); + assertEquals(200, group.priority(), "Priority was not inherited"); + } } diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java index 2644386d522..90d2dfffef9 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java @@ -51,7 +51,7 @@ void cancelOnInterruptDoesNotResume() { } @Test - void scheduleOverDefaultDoesNotRescheduleDefault() { + void defaultCommandResumesAfterInterruption() { var count = new AtomicInteger(0); var mechanism = new Mechanism("mechanism", m_scheduler); @@ -78,7 +78,8 @@ void scheduleOverDefaultDoesNotRescheduleDefault() { assertEquals(1, count.get(), "Default command should have run once"); m_scheduler.run(); - assertTrue(m_scheduler.isRunning(defaultCmd)); + assertTrue(m_scheduler.isRunning(defaultCmd), "Default command should have resumed"); + assertEquals(2, count.get()); } @Test @@ -185,13 +186,7 @@ void cancelAllStartsDefaults() { // Then ticking the scheduler once to fully remove the command and schedule the defaults m_scheduler.run(); - // Then one more tick to start running the scheduled defaults - m_scheduler.run(); - - if (m_scheduler.isRunning(command)) { - System.err.println(m_scheduler.getRunningCommands()); - fail(command.name() + " was not canceled by cancelAll()"); - } + assertFalse(m_scheduler.isRunning(command), "Command was not canceled by cancelAll()"); for (var mechanism : mechanisms) { var runningCommands = m_scheduler.getRunningCommandsFor(mechanism); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java index 2a339822b51..a4823fea4d0 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java @@ -40,7 +40,7 @@ void compositionsCannotAwaitConflictingCommands() { } @Test - void siblingsInCompositionCanShareRequirements() { + void innerCommandMayInterruptOtherInnerCommand() { var mechanism = new Mechanism("The mechanism", m_scheduler); var firstRan = new AtomicBoolean(false); var secondRan = new AtomicBoolean(false); @@ -146,8 +146,8 @@ void childConflictsWithLowerPriorityTopLevel() { var mechanism = new Mechanism("mechanism", m_scheduler); var top = mechanism.run(Coroutine::park).withPriority(-10).named("Top"); - // Child conflicts with and is lower priority than the Top command - // It should not be scheduled, and the parent command should exit immediately + // Child conflicts with and is higher priority than the Top command + // It should be scheduled, and the top command should be interrupted var child = mechanism.run(Coroutine::park).named("Child"); var parent = Command.noRequirements().executing(co -> co.await(child)).named("Parent"); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java index 4c66f41edaf..3e65aa81632 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java @@ -6,7 +6,6 @@ import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; -import static org.junit.jupiter.api.Assertions.fail; import org.junit.jupiter.api.Test; @@ -41,12 +40,9 @@ void lowerPriorityDoesNotCancel() { m_scheduler.schedule(lower); m_scheduler.run(); - if (!m_scheduler.isRunning(higher)) { - fail("Higher priority command should still be running"); - } - if (m_scheduler.isRunning(lower)) { - fail("Lower priority command should not be running"); - } + assertTrue(m_scheduler.isRunning(higher), "Higher priority command should still be running"); + assertFalse( + m_scheduler.isScheduledOrRunning(lower), "Lower priority command should not be running"); } @Test diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java index ecd49a225a7..7181cdf6f89 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java @@ -36,27 +36,74 @@ void commandAwaitingItself() { @Test void commandDeadlock() { + AtomicReference parentRef = new AtomicReference<>(); + AtomicReference childRef = new AtomicReference<>(); + + // Deadlock scenario: + // parent starts, schedules child, then waits for child to exit + // child starts, waits for parent to exit + // + // Each successive run sees parent mount, check for child, then yield. + // Then sees child mount, check for parent, then also yield. + // This is like two threads spinwaiting for the other to exit. + // + // Externally canceling child allows parent to continue + // Externally canceling parent cancels both + var parent = Command.noRequirements().executing(co -> co.await(childRef.get())).named("Parent"); + var child = Command.noRequirements().executing(co -> co.await(parentRef.get())).named("Child"); + parentRef.set(parent); + childRef.set(child); + + m_scheduler.schedule(parent); + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(parent)); + assertTrue(m_scheduler.isRunning(child)); + + m_scheduler.run(); + assertTrue(m_scheduler.isRunning(parent)); + assertTrue(m_scheduler.isRunning(child)); + + m_scheduler.cancel(parent); + m_scheduler.run(); + assertFalse(m_scheduler.isRunning(parent)); + assertFalse(m_scheduler.isRunning(child)); + } + + @Test + void delayedCommandDeadlock() { AtomicReference ref1 = new AtomicReference<>(); AtomicReference ref2 = new AtomicReference<>(); // Deadlock scenario: - // command1 starts, schedules command2, then waits for command2 to exit + // command1 starts, waits for command2 to exit // command2 starts, waits for command1 to exit // // Each successive run sees command1 mount, check for command2, then yield. // Then sees command2 mount, check for command1, then also yield. // This is like two threads spinwaiting for the other to exit. // - // Externally canceling command2 allows command1 to continue - // Externally canceling command1 cancels both + // Externally canceling either command allows the other to exit var command1 = - Command.noRequirements().executing(co -> co.await(ref2.get())).named("Command 1"); + Command.noRequirements() + .executing( + co -> { + co.yield(); + co.await(ref2.get()); + }) + .named("Command 1"); var command2 = - Command.noRequirements().executing(co -> co.await(ref1.get())).named("Command 2"); + Command.noRequirements() + .executing( + co -> { + co.yield(); + co.await(ref1.get()); + }) + .named("Command 2"); ref1.set(command1); ref2.set(command2); m_scheduler.schedule(command1); + m_scheduler.schedule(command2); m_scheduler.run(); assertTrue(m_scheduler.isRunning(command1)); assertTrue(m_scheduler.isRunning(command2)); @@ -65,7 +112,7 @@ void commandDeadlock() { assertTrue(m_scheduler.isRunning(command1)); assertTrue(m_scheduler.isRunning(command2)); - m_scheduler.cancel(command1); + m_scheduler.cancel(command2); m_scheduler.run(); assertFalse(m_scheduler.isRunning(command1)); assertFalse(m_scheduler.isRunning(command2)); diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java index 6bfa82c31c0..4481ee8181f 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java @@ -4,10 +4,12 @@ package org.wpilib.commands3; +import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; import java.util.List; +import java.util.Set; import org.junit.jupiter.api.Test; class SequentialGroupTest extends CommandTestBase { @@ -57,4 +59,24 @@ void twoCommands() { assertFalse(m_scheduler.isRunning(sequence)); assertFalse(m_scheduler.isRunning(c2), "Second command should have started"); } + + @Test + void inheritsRequirements() { + var mech1 = new Mechanism("Mech 1", m_scheduler); + var mech2 = new Mechanism("Mech 2", m_scheduler); + var command1 = mech1.run(Coroutine::park).named("Command 1"); + var command2 = mech2.run(Coroutine::park).named("Command 2"); + var sequence = new SequentialGroup("Sequence", List.of(command1, command2)); + assertEquals(Set.of(mech1, mech2), sequence.requirements(), "Requirements were not inherited"); + } + + @Test + void inheritsPriority() { + var mech1 = new Mechanism("Mech 1", m_scheduler); + var mech2 = new Mechanism("Mech 2", m_scheduler); + var command1 = mech1.run(Coroutine::park).withPriority(100).named("Command 1"); + var command2 = mech2.run(Coroutine::park).withPriority(200).named("Command 2"); + var sequence = new SequentialGroup("Sequence", List.of(command1, command2)); + assertEquals(200, sequence.priority(), "Priority was not inherited"); + } } From 966cfa041ee36ca932186aa261df587b11be24cd Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 26 Sep 2025 09:32:57 -0400 Subject: [PATCH 146/153] Gradle updates --- commandsv3/build.gradle | 20 ++++++++++---------- wpilibjExamples/build.gradle | 1 - 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index e5aeca7a217..90a166f31f9 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -5,7 +5,7 @@ ext { groupId = 'org.wpilib' nativeName = 'commands3' - devMain = '' + devMain = 'org.wpilib.commands3.DevMain' } apply from: "${rootDir}/shared/java/javacommon.gradle" @@ -23,7 +23,7 @@ dependencies { implementation project(':hal') implementation project(':wpimath') implementation project(':wpilibj') - api("us.hebi.quickbuf:quickbuf-runtime:1.3.3") + api("us.hebi.quickbuf:quickbuf-runtime:1.4") testImplementation 'org.mockito:mockito-core:4.1.0' } @@ -35,12 +35,12 @@ test { outputs.upToDateWhen {false} showStandardStreams = true } - doFirst { - jvmArgs = [ - '--add-opens', - 'java.base/jdk.internal.vm=ALL-UNNAMED', - '--add-opens', - 'java.base/java.lang=ALL-UNNAMED', - ] - } + + // For reflective access to the continuation classes + jvmArgs += [ + '--add-opens', + 'java.base/jdk.internal.vm=ALL-UNNAMED', + '--add-opens', + 'java.base/java.lang=ALL-UNNAMED', + ] } diff --git a/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle index 744d6e6723a..e2269a19750 100644 --- a/wpilibjExamples/build.gradle +++ b/wpilibjExamples/build.gradle @@ -22,7 +22,6 @@ dependencies { implementation project(':cscore') implementation project(':cameraserver') implementation project(':wpilibNewCommands') - implementation project(':commandsv3') implementation project(':romiVendordep') implementation project(':xrpVendordep') implementation project(':epilogue-runtime') From ca98b4ba1b3b71b33c5b469cd60e4d916111906f Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Fri, 3 Oct 2025 09:18:44 -0400 Subject: [PATCH 147/153] Add explicit check for command 1 completing normally --- .../org/wpilib/commands3/SchedulerTimingTests.java | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java index 7181cdf6f89..1643c7777f2 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTimingTests.java @@ -74,6 +74,9 @@ void delayedCommandDeadlock() { AtomicReference ref1 = new AtomicReference<>(); AtomicReference ref2 = new AtomicReference<>(); + AtomicBoolean command1CompletedNormally = new AtomicBoolean(false); + AtomicBoolean command2CompletedNormally = new AtomicBoolean(false); + // Deadlock scenario: // command1 starts, waits for command2 to exit // command2 starts, waits for command1 to exit @@ -89,6 +92,7 @@ void delayedCommandDeadlock() { co -> { co.yield(); co.await(ref2.get()); + command1CompletedNormally.set(true); }) .named("Command 1"); var command2 = @@ -97,6 +101,7 @@ void delayedCommandDeadlock() { co -> { co.yield(); co.await(ref1.get()); + command2CompletedNormally.set(true); }) .named("Command 2"); ref1.set(command1); @@ -116,6 +121,12 @@ void delayedCommandDeadlock() { m_scheduler.run(); assertFalse(m_scheduler.isRunning(command1)); assertFalse(m_scheduler.isRunning(command2)); + assertTrue( + command1CompletedNormally.get(), + "Command 1 should have completed normally after command 2 stopped"); + assertFalse( + command2CompletedNormally.get(), + "Canceling command 2 should have stopped it before completing"); } @Test From 7a3fe6ea9559fb1bdcfbb0d035189759a53bd3ef Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 7 Oct 2025 12:45:47 -0400 Subject: [PATCH 148/153] Add NoDiscard to command types --- commandsv3/build.gradle | 3 +++ .../java/org/wpilib/commands3/Command.java | 8 +++++++ .../java/org/wpilib/commands3/Mechanism.java | 3 +++ .../commands3/NeedsExecutionBuilderStage.java | 2 ++ .../commands3/NeedsNameBuilderStage.java | 2 ++ .../commands3/ParallelGroupBuilder.java | 2 ++ .../java/org/wpilib/commands3/Scheduler.java | 7 ++++++ .../commands3/SequentialGroupBuilder.java | 2 ++ .../commands3/StagedCommandBuilder.java | 2 ++ .../commands3/StagedCommandBuilderTest.java | 22 +++++++++---------- 10 files changed, 42 insertions(+), 11 deletions(-) diff --git a/commandsv3/build.gradle b/commandsv3/build.gradle index 90a166f31f9..b097060d1d5 100644 --- a/commandsv3/build.gradle +++ b/commandsv3/build.gradle @@ -17,6 +17,8 @@ evaluationDependsOn(':wpimath') evaluationDependsOn(':wpilibj') dependencies { + annotationProcessor project(':javacPlugin') + implementation project(':wpiannotations') implementation project(':wpiutil') implementation project(':wpinet') implementation project(':ntcore') @@ -24,6 +26,7 @@ dependencies { implementation project(':wpimath') implementation project(':wpilibj') api("us.hebi.quickbuf:quickbuf-runtime:1.4") + testAnnotationProcessor project(':javacPlugin') testImplementation 'org.mockito:mockito-core:4.1.0' } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Command.java b/commandsv3/src/main/java/org/wpilib/commands3/Command.java index 11c187c4238..4e75a6918ba 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Command.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Command.java @@ -12,6 +12,7 @@ import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Consumer; +import org.wpilib.annotation.NoDiscard; /** * Performs some task using one or more {@link Mechanism mechanisms}. Commands are fundamentally @@ -93,6 +94,7 @@ * } * }

    */ +@NoDiscard("Commands must be used! Did you mean to fork it or bind it to a trigger?") public interface Command { /** The default command priority. */ int DEFAULT_PRIORITY = 0; @@ -136,6 +138,7 @@ default void onCancel() { * * @return the name of the command */ + @NoDiscard String name(); /** @@ -145,6 +148,7 @@ default void onCancel() { * * @return the set of mechanisms required by the command */ + @NoDiscard Set requirements(); /** @@ -156,6 +160,7 @@ default void onCancel() { * * @return the priority of the command */ + @NoDiscard default int priority() { return DEFAULT_PRIORITY; } @@ -166,6 +171,7 @@ default int priority() { * @param other the command to compare with * @return true if this command has a lower priority than the other one, false otherwise */ + @NoDiscard default boolean isLowerPriorityThan(Command other) { requireNonNullParam(other, "other", "Command.isLowerPriorityThan"); @@ -178,6 +184,7 @@ default boolean isLowerPriorityThan(Command other) { * @param mechanism the mechanism to check * @return true if the mechanism is required, false if not */ + @NoDiscard default boolean requires(Mechanism mechanism) { return requirements().contains(mechanism); } @@ -189,6 +196,7 @@ default boolean requires(Mechanism mechanism) { * @return true if both commands require at least one of the same mechanism, false if both * commands have completely different requirements */ + @NoDiscard default boolean conflictsWith(Command other) { requireNonNullParam(other, "other", "Command.conflictsWith"); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java index 2ef1a6fd705..4d8e41ac4c3 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java @@ -7,6 +7,7 @@ import edu.wpi.first.units.measure.Time; import java.util.List; import java.util.function.Consumer; +import org.wpilib.annotation.NoDiscard; /** * Generic base class to represent mechanisms on a robot. Commands can require sole ownership of a @@ -61,6 +62,7 @@ public Mechanism(String name, Scheduler scheduler) { * * @return The name of the mechanism. */ + @NoDiscard public String getName() { return m_name; } @@ -151,6 +153,7 @@ public Command idleFor(Time duration) { * * @return The currently running commands that require the mechanism. */ + @NoDiscard public List getRunningCommands() { return m_registeredScheduler.getRunningCommandsFor(this); } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java b/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java index f781ce502e1..23b5b2f641e 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/NeedsExecutionBuilderStage.java @@ -6,6 +6,7 @@ import java.util.Collection; import java.util.function.Consumer; +import org.wpilib.annotation.NoDiscard; /** * A stage in a command builder where requirements have already been specified and execution details @@ -13,6 +14,7 @@ * #executing(Consumer)}. Additional requirements may still be added before moving on to the next * stage. */ +@NoDiscard public interface NeedsExecutionBuilderStage { /** * Adds a required mechanism for the command. diff --git a/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java index 13036bc066d..d89691a6bad 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/NeedsNameBuilderStage.java @@ -6,12 +6,14 @@ import java.util.function.BooleanSupplier; import java.util.function.Consumer; +import org.wpilib.annotation.NoDiscard; /** * A stage in a command builder where requirements and main command execution logic have been set. * No more changes to requirements or command implementation may happen after this point. This is * the final step in command creation */ +@NoDiscard public interface NeedsNameBuilderStage { /** * Optionally sets a callback to execute when the command is canceled. The callback will not run diff --git a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java index 6092f9eecde..e5660ebd230 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/ParallelGroupBuilder.java @@ -11,6 +11,7 @@ import java.util.Set; import java.util.function.BooleanSupplier; import java.util.stream.Collectors; +import org.wpilib.annotation.NoDiscard; /** * A builder class to configure and then create a {@link ParallelGroup}. Like {@link @@ -18,6 +19,7 @@ * #named(String)} method, or with an automatically generated name using {@link * #withAutomaticName()}. */ +@NoDiscard public class ParallelGroupBuilder { private final Set m_commands = new LinkedHashSet<>(); private final Set m_requiredCommands = new LinkedHashSet<>(); diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java index 5514af7231a..752b7792533 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Scheduler.java @@ -26,6 +26,7 @@ import java.util.Stack; import java.util.function.Consumer; import java.util.stream.Collectors; +import org.wpilib.annotation.NoDiscard; import org.wpilib.commands3.button.CommandGenericHID; import org.wpilib.commands3.proto.SchedulerProto; @@ -140,6 +141,7 @@ public final class Scheduler implements ProtobufSerializable { * * @return the default scheduler instance. */ + @NoDiscard public static Scheduler getDefault() { return s_defaultScheduler; } @@ -153,6 +155,7 @@ public static Scheduler getDefault() { * * @return a new scheduler instance that is independent of the default scheduler instance. */ + @NoDiscard public static Scheduler createIndependentScheduler() { return new Scheduler(); } @@ -800,6 +803,7 @@ public void cancelAll() { * * @return the default event loop. */ + @NoDiscard public EventLoop getDefaultEventLoop() { return m_eventLoop; } @@ -809,6 +813,7 @@ public EventLoop getDefaultEventLoop() { * * @return The commands that have been scheduled but not yet started. */ + @NoDiscard public Collection getQueuedCommands() { return m_queuedToRun.stream().map(CommandState::command).toList(); } @@ -866,6 +871,7 @@ public double totalRuntimeMs(Command command) { * @param command The command to get the run ID for * @return The run of the command */ + @NoDiscard @SuppressWarnings("PMD.CompareObjectsWithEquals") public int runId(Command command) { if (m_runningCommands.containsKey(command)) { @@ -888,6 +894,7 @@ public int runId(Command command) { * * @return How long, in milliseconds, the scheduler last took to execute. */ + @NoDiscard public double lastRuntimeMs() { return m_lastRunTimeMs; } diff --git a/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java index 28048e10318..5c10a61aa40 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/SequentialGroupBuilder.java @@ -11,6 +11,7 @@ import java.util.List; import java.util.function.BooleanSupplier; import java.util.stream.Collectors; +import org.wpilib.annotation.NoDiscard; /** * A builder class to configure and then create a {@link SequentialGroup}. Like {@link @@ -18,6 +19,7 @@ * #named(String)} method, or with an automatically generated name using {@link * #withAutomaticName()}. */ +@NoDiscard public class SequentialGroupBuilder { private final List m_steps = new ArrayList<>(); private BooleanSupplier m_endCondition; diff --git a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java index ed4cbc6138b..5b68ce56020 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/StagedCommandBuilder.java @@ -13,6 +13,7 @@ import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Consumer; +import org.wpilib.annotation.NoDiscard; /** * A builder class for commands. Command configuration is done in stages, where later stages have @@ -52,6 +53,7 @@ * .named("Example Command"); * }
    */ +@NoDiscard public final class StagedCommandBuilder { private final Set m_requirements = new HashSet<>(); private Consumer m_impl; diff --git a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java index a7d05458134..ec85cfeb3a8 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java @@ -64,7 +64,7 @@ void allOptions() { @Test void starting_noRequirements_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - builder.noRequirements().executing(c -> {}).named("cmd"); + var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, builder::noRequirements); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -73,7 +73,7 @@ void starting_noRequirements_throwsAfterBuild() { @Test void starting_requiringVarargs_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - builder.noRequirements().executing(c -> {}).named("cmd"); + var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> builder.requiring(m_mech1, m_mech2)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -82,7 +82,7 @@ void starting_requiringVarargs_throwsAfterBuild() { @Test void starting_requiringCollection_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - builder.noRequirements().executing(c -> {}).named("cmd"); + var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows( @@ -94,7 +94,7 @@ void starting_requiringCollection_throwsAfterBuild() { void requirements_requiringSingle_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - reqStage.executing(c -> {}).named("cmd"); + var ignore = reqStage.executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -104,7 +104,7 @@ void requirements_requiringSingle_throwsAfterBuild() { void requirements_requiringVarargs_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - reqStage.executing(Coroutine::park).named("cmd"); + var ignore = reqStage.executing(Coroutine::park).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1, m_mech2)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -114,7 +114,7 @@ void requirements_requiringVarargs_throwsAfterBuild() { void requirements_requiringCollection_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - reqStage.executing(Coroutine::park).named("cmd"); + var ignore = reqStage.executing(Coroutine::park).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(List.of(m_mech1))); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -124,7 +124,7 @@ void requirements_requiringCollection_throwsAfterBuild() { void requirements_executing_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - reqStage.executing(c -> {}).named("cmd"); + var ignore = reqStage.executing(c -> {}).named("cmd"); Consumer impl = Coroutine::park; var err = assertThrows(IllegalStateException.class, () -> reqStage.executing(impl)); @@ -135,7 +135,7 @@ void requirements_executing_throwsAfterBuild() { void execution_whenCanceled_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - execStage.named("cmd"); + var ignore = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.whenCanceled(() -> {})); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -145,7 +145,7 @@ void execution_whenCanceled_throwsAfterBuild() { void execution_withPriority_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - execStage.named("cmd"); + var ignore = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.withPriority(7)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -155,7 +155,7 @@ void execution_withPriority_throwsAfterBuild() { void execution_until_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - execStage.named("cmd"); + var ignore = execStage.named("cmd"); BooleanSupplier endCondition = () -> true; var err = assertThrows(IllegalStateException.class, () -> execStage.until(endCondition)); @@ -166,7 +166,7 @@ void execution_until_throwsAfterBuild() { void execution_named_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - execStage.named("cmd"); + var ignore = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.named("other")); assertEquals("Command builders cannot be reused", err.getMessage()); From 3ccd430af0941f16b3115bf390e24410cb6ce18c Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 7 Oct 2025 19:43:32 -0400 Subject: [PATCH 149/153] Linting --- .../commands3/StagedCommandBuilderTest.java | 22 +++++++++---------- styleguide/spotbugs-exclude.xml | 5 +++++ 2 files changed, 16 insertions(+), 11 deletions(-) diff --git a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java index ec85cfeb3a8..44fef542a89 100644 --- a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java +++ b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java @@ -64,7 +64,7 @@ void allOptions() { @Test void starting_noRequirements_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); + var ignored = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, builder::noRequirements); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -73,7 +73,7 @@ void starting_noRequirements_throwsAfterBuild() { @Test void starting_requiringVarargs_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); + var ignored = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> builder.requiring(m_mech1, m_mech2)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -82,7 +82,7 @@ void starting_requiringVarargs_throwsAfterBuild() { @Test void starting_requiringCollection_throwsAfterBuild() { var builder = new StagedCommandBuilder(); - var ignore = builder.noRequirements().executing(c -> {}).named("cmd"); + var ignored = builder.noRequirements().executing(c -> {}).named("cmd"); var err = assertThrows( @@ -94,7 +94,7 @@ void starting_requiringCollection_throwsAfterBuild() { void requirements_requiringSingle_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - var ignore = reqStage.executing(c -> {}).named("cmd"); + var ignored = reqStage.executing(c -> {}).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -104,7 +104,7 @@ void requirements_requiringSingle_throwsAfterBuild() { void requirements_requiringVarargs_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - var ignore = reqStage.executing(Coroutine::park).named("cmd"); + var ignored = reqStage.executing(Coroutine::park).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(m_mech1, m_mech2)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -114,7 +114,7 @@ void requirements_requiringVarargs_throwsAfterBuild() { void requirements_requiringCollection_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - var ignore = reqStage.executing(Coroutine::park).named("cmd"); + var ignored = reqStage.executing(Coroutine::park).named("cmd"); var err = assertThrows(IllegalStateException.class, () -> reqStage.requiring(List.of(m_mech1))); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -124,7 +124,7 @@ void requirements_requiringCollection_throwsAfterBuild() { void requirements_executing_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var reqStage = builder.noRequirements(); - var ignore = reqStage.executing(c -> {}).named("cmd"); + var ignored = reqStage.executing(c -> {}).named("cmd"); Consumer impl = Coroutine::park; var err = assertThrows(IllegalStateException.class, () -> reqStage.executing(impl)); @@ -135,7 +135,7 @@ void requirements_executing_throwsAfterBuild() { void execution_whenCanceled_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - var ignore = execStage.named("cmd"); + var ignored = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.whenCanceled(() -> {})); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -145,7 +145,7 @@ void execution_whenCanceled_throwsAfterBuild() { void execution_withPriority_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - var ignore = execStage.named("cmd"); + var ignored = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.withPriority(7)); assertEquals("Command builders cannot be reused", err.getMessage()); @@ -155,7 +155,7 @@ void execution_withPriority_throwsAfterBuild() { void execution_until_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - var ignore = execStage.named("cmd"); + var ignored = execStage.named("cmd"); BooleanSupplier endCondition = () -> true; var err = assertThrows(IllegalStateException.class, () -> execStage.until(endCondition)); @@ -166,7 +166,7 @@ void execution_until_throwsAfterBuild() { void execution_named_throwsAfterBuild() { var builder = new StagedCommandBuilder(); var execStage = builder.noRequirements().executing(c -> {}); - var ignore = execStage.named("cmd"); + var ignored = execStage.named("cmd"); var err = assertThrows(IllegalStateException.class, () -> execStage.named("other")); assertEquals("Command builders cannot be reused", err.getMessage()); diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml index bdebdc55f3e..ac00f14803b 100644 --- a/styleguide/spotbugs-exclude.xml +++ b/styleguide/spotbugs-exclude.xml @@ -205,6 +205,11 @@ + + + + + From 9473a2d4d0705763d617bb2fddfaa1c0014cebc2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 7 Oct 2025 19:47:36 -0400 Subject: [PATCH 150/153] Update cmake to include commandsv3 with wpilib build --- CMakeLists.txt | 2 ++ README-CMake.md | 1 + commandsv3/CMakeLists.txt | 11 ++++------- wpilib-config.cmake.in | 1 + 4 files changed, 8 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 71fce234976..6d6d4c80c8a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -346,12 +346,14 @@ endif() if(WITH_WPILIB) set(APRILTAG_DEP_REPLACE "find_dependency(apriltag)") + set(COMMANDSV3_DEP_REPLACE "find_dependency(commandsv3)") set(WPILIBC_DEP_REPLACE "find_dependency(wpilibc)") set(WPILIBJ_DEP_REPLACE "find_dependency(wpilibj)") set(WPILIBNEWCOMMANDS_DEP_REPLACE "find_dependency(wpilibNewCommands)") add_subdirectory(apriltag) add_subdirectory(wpilibj) add_subdirectory(wpilibc) + add_subdirectory(commandsv3) # must be after wpilibj add_subdirectory(wpilibNewCommands) add_subdirectory(romiVendordep) add_subdirectory(xrpVendordep) diff --git a/README-CMake.md b/README-CMake.md index eaa954d2d19..a91885f19ac 100644 --- a/README-CMake.md +++ b/README-CMake.md @@ -5,6 +5,7 @@ WPILib is normally built with Gradle, however for some systems, such as Linux ba ## Libraries that get built * apriltag * cameraserver +* commandsv3 * cscore * fieldImages * hal (simulation HAL only) diff --git a/commandsv3/CMakeLists.txt b/commandsv3/CMakeLists.txt index d37bff6b4df..d50c6a4971b 100644 --- a/commandsv3/CMakeLists.txt +++ b/commandsv3/CMakeLists.txt @@ -8,6 +8,8 @@ if(WITH_JAVA) include(UseJava) file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) + file(GLOB QUICKBUF_JAR ${WPILIB_BINARY_DIR}/wpiutil/thirdparty/quickbuf/*.jar) + add_jar( commandsv3_jar ${JAVA_SOURCES} @@ -17,10 +19,12 @@ if(WITH_JAVA) ntcore_jar cscore_jar cameraserver_jar + wpiannotations_jar wpimath_jar wpiunits_jar wpiutil_jar wpilibj_jar + ${QUICKBUF_JAR} OUTPUT_NAME commandsv3 OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) @@ -47,10 +51,3 @@ if(WITH_JAVA_SOURCE) set_property(TARGET commandsv3_src_jar PROPERTY FOLDER "java") install_jar(commandsv3_src_jar DESTINATION ${java_lib_dest}) endif() - -install(TARGETS commandsv3 EXPORT commandsv3) -export(TARGETS commandsv3 FILE commandsv3.cmake NAMESPACE commandsv3::) - -configure_file(commandsv3-config.cmake.in ${WPILIB_BINARY_DIR}/commandsv3-config.cmake) -install(FILES ${WPILIB_BINARY_DIR}/commandsv3-config.cmake DESTINATION share/commandsv3) -install(EXPORT commandsv3 DESTINATION share/commandsv3) diff --git a/wpilib-config.cmake.in b/wpilib-config.cmake.in index 30080f24d9b..1c3bb90ac63 100644 --- a/wpilib-config.cmake.in +++ b/wpilib-config.cmake.in @@ -8,6 +8,7 @@ find_dependency(Threads) @APRILTAG_DEP_REPLACE@ @CAMERASERVER_DEP_REPLACE@ @CSCORE_DEP_REPLACE@ +@COMMANDSV3_DEP_REPLACE@ @DATALOG_DEP_REPLACE@ @HAL_DEP_REPLACE@ @NTCORE_DEP_REPLACE@ From 4a89bf1aaf9173bbdae563085142975148b4f4ea Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Tue, 7 Oct 2025 20:43:17 -0400 Subject: [PATCH 151/153] Add wpiannotations to bazel dependencies --- commandsv3/BUILD.bazel | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/commandsv3/BUILD.bazel b/commandsv3/BUILD.bazel index d7b63f99095..29166305657 100644 --- a/commandsv3/BUILD.bazel +++ b/commandsv3/BUILD.bazel @@ -44,13 +44,16 @@ filegroup( wpilib_java_library( name = "commandsv3-java", srcs = glob(["src/main/java/**/*.java"]) + [":generated_java"], + exported_plugins = ["//javacPlugin:plugin"], maven_artifact_name = "commands3-java", maven_group_id = "org.wpilib.commands3", + plugins = ["//javacPlugin:plugin"], visibility = ["//visibility:public"], deps = [ "//cscore:cscore-java", "//hal:hal-java", "//ntcore:ntcore-java", + "//wpiannotations", "//wpilibj:wpilibj-java", "//wpimath:wpimath-java", "//wpinet:wpinet-java", @@ -67,6 +70,7 @@ wpilib_java_junit5_test( ":commandsv3-java", "//hal:hal-java", "//ntcore:ntcore-java", + "//wpiannotations", "//wpilibj:wpilibj-java", "//wpimath:wpimath-java", "//wpiunits:wpiunits-java", From efbf0c321a7aa12f6b03115669a1fe42087f9275 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 9 Oct 2025 09:17:19 -0400 Subject: [PATCH 152/153] Add datalog to cmake deps --- commandsv3/commandsv3-config.cmake.in | 1 + 1 file changed, 1 insertion(+) diff --git a/commandsv3/commandsv3-config.cmake.in b/commandsv3/commandsv3-config.cmake.in index 8b988a1c95a..30194c4250c 100644 --- a/commandsv3/commandsv3-config.cmake.in +++ b/commandsv3/commandsv3-config.cmake.in @@ -1,5 +1,6 @@ include(CMakeFindDependencyMacro) @WPIUTIL_DEP_REPLACE@ +@DATALOG_DEP_REPLACE@ @NTCORE_DEP_REPLACE@ @CSCORE_DEP_REPLACE@ @CAMERASERVER_DEP_REPLACE@ From fee4a8fd938e9c652020291bf133c3831db934bb Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Thu, 9 Oct 2025 18:29:57 -0400 Subject: [PATCH 153/153] Add null check for binding frames --- commandsv3/src/main/java/org/wpilib/commands3/Binding.java | 1 + 1 file changed, 1 insertion(+) diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java index 41879e991c8..69943c22c5a 100644 --- a/commandsv3/src/main/java/org/wpilib/commands3/Binding.java +++ b/commandsv3/src/main/java/org/wpilib/commands3/Binding.java @@ -21,5 +21,6 @@ record Binding(BindingScope scope, BindingType type, Command command, StackTrace ErrorMessages.requireNonNullParam(scope, "scope", "Binding"); ErrorMessages.requireNonNullParam(type, "type", "Binding"); ErrorMessages.requireNonNullParam(command, "command", "Binding"); + ErrorMessages.requireNonNullParam(frames, "frames", "Binding"); } }