Package org.hyperonline.hyperlib
Class QuickCommand
- java.lang.Object
-
- org.hyperonline.hyperlib.QuickCommand
-
public class QuickCommand extends java.lang.ObjectTheQuickCommandclass provides helper methods to make short commands. This removes the need to make a new class for every small command, and thus helps quick development and simplifies code.If you want to make a command that runs once and finishes instantly, use
oneShot. If you want to make a command that runs continuously until it is interrupted, usecontinuous. If you want to make a command that runs until a specific condition is met, useuntilorwaitFor.For example, the following code makes a command that will call
exampleSubsystem.doSomething()once and then end:{ @code Command myCmd = QuickCommand.oneShot(Robot.exampleSubsystem, () -> Robot.exampleSubsystem.doSomething()); }For more information on the syntax used, look up Java lambda expressions.Any more advanced features, like custom conditions for
isFinished, compound commands, or commands that require multiple or no subsystems, subclassCommandin the usual way.
-
-
Constructor Summary
Constructors Constructor Description QuickCommand()
-
Method Summary
All Methods Static Methods Concrete Methods Modifier and Type Method Description static edu.wpi.first.wpilibj.command.Commandcontinuous(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body)Create a command that will run until interrupted.static edu.wpi.first.wpilibj.command.CommandoneShot(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body)Create a command that will run once and finish instantly.static edu.wpi.first.wpilibj.command.CommandpidHold(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source)Constructs a Command that holds aPIDControllerat whatever the current input is.static edu.wpi.first.wpilibj.command.CommandpidMove(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, double setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem.static edu.wpi.first.wpilibj.command.CommandpidMove(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, java.util.function.DoubleSupplier setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem.static edu.wpi.first.wpilibj.command.CommandpidMoveContinuous(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, java.util.function.DoubleSupplier setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem.static edu.wpi.first.wpilibj.command.CommandpidMoveOver(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source, double target, boolean hold)Constructs a command that moves aPIDControllerto be over a given target, only if the current position is under that target.static edu.wpi.first.wpilibj.command.CommandpidMoveUnder(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source, double target, boolean hold)Constructs a command that moves aPIDControllerto be under a given target, only if the current position is over that target.static edu.wpi.first.wpilibj.command.Commandrelease(edu.wpi.first.wpilibj.command.Subsystem subsystem)Create a command which releases control of a subsystem.static edu.wpi.first.wpilibj.command.CommandrunIf(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body, java.util.function.BooleanSupplier finished, java.util.function.BooleanSupplier runnable)Create a command that will run if the runnable condition is met, and if so until the finished condition is met.static edu.wpi.first.wpilibj.command.CommandrunUntil(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body, java.util.function.BooleanSupplier finished)Create a command that will run until the given condition is met.static edu.wpi.first.wpilibj.command.CommandwaitFor(java.util.function.BooleanSupplier condition)A command that does not complete until the given condition is met.
-
-
-
Method Detail
-
oneShot
public static edu.wpi.first.wpilibj.command.Command oneShot(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body)Create a command that will run once and finish instantly.- Parameters:
req- TheSubsystemthat this command requires.body- TheRunnablethat will run once.- Returns:
- The newly created
Command
-
continuous
public static edu.wpi.first.wpilibj.command.Command continuous(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body)Create a command that will run until interrupted.- Parameters:
req- TheSubsystemthat this command requires.body- TheRunnablethat will run repeatedly.- Returns:
- The newly created
Command
-
runUntil
public static edu.wpi.first.wpilibj.command.Command runUntil(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body, java.util.function.BooleanSupplier finished)Create a command that will run until the given condition is met.- Parameters:
req- TheSubsystemthat this command requires.body- TheRunnablethat will run repeatedly.finished- The condition that signals the end of the command.- Returns:
- The newly created
Command
-
runIf
public static edu.wpi.first.wpilibj.command.Command runIf(edu.wpi.first.wpilibj.command.Subsystem req, java.lang.Runnable body, java.util.function.BooleanSupplier finished, java.util.function.BooleanSupplier runnable)Create a command that will run if the runnable condition is met, and if so until the finished condition is met.- Parameters:
req- TheSubsystemthat this command requires.body- TheRunnablethat will run repeatedly.finished- The condition that signals the end of the command.runnable- The condition that signals the command should be run- Returns:
- The newly created
Command
-
waitFor
public static edu.wpi.first.wpilibj.command.Command waitFor(java.util.function.BooleanSupplier condition)
A command that does not complete until the given condition is met. This can be useful when combined withCommandGroup.addSequential(Command)andCommandGroup.addParallel(Command)- Parameters:
condition- The condition that indicates the command is over- Returns:
- The newly created
Command
-
pidMove
public static edu.wpi.first.wpilibj.command.Command pidMove(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, double setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem. The pid controller is enabled when the command starts and disabled when it ends or is interrupted.- Parameters:
req- The subsystem to requirepid- The PID controller to usesetPoint- The point to move the PID controller tohold- Whether or not to continue running the PID loop after the target setpoint is reached- Returns:
- The newly created
Command
-
pidMove
public static edu.wpi.first.wpilibj.command.Command pidMove(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, java.util.function.DoubleSupplier setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem. The pid controller is enabled when the command starts and disabled when it ends or is interrupted.- Parameters:
req- The subsystem to requirepid- The PID controller to usesetPoint- The point to move the PID controller tohold- Whether or not to continue running the PID loop after the target setpoint is reached- Returns:
- The newly created
Command
-
pidMoveContinuous
public static edu.wpi.first.wpilibj.command.Command pidMoveContinuous(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, java.util.function.DoubleSupplier setPoint, boolean hold)Constructs a command that uses aPIDControllerto control a subsystem. The pid controller is enabled when the command starts and disabled when it ends or is interrupted.- Parameters:
req- The subsystem to requirepid- The PID controller to usesetPoint- The point to move the PID controller tohold- Whether or not to continue running the PID loop after the target setpoint is reached- Returns:
- The newly created
Command
-
pidHold
public static edu.wpi.first.wpilibj.command.Command pidHold(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source)Constructs a Command that holds aPIDControllerat whatever the current input is. This is useful in combination with a manual control system, where you want to move the system manually but hold it in place using PID.- Parameters:
req- The Subsystem to requirepid- The PIDController to usesource- The PIDSource (encoder, potentiometer, etc.) from which to take the input- Returns:
- The newly created command
-
pidMoveUnder
public static edu.wpi.first.wpilibj.command.Command pidMoveUnder(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source, double target, boolean hold)Constructs a command that moves aPIDControllerto be under a given target, only if the current position is over that target.- Parameters:
req- The subsystem to requirepid- The PID controller to usesource- The PIDSource (encoder, potentiometer, etc.) from which to take the inputtarget- The point to move the PID controller underhold- Whether or not to continue running the PID loop after the target is reached- Returns:
- The newly created
Command
-
pidMoveOver
public static edu.wpi.first.wpilibj.command.Command pidMoveOver(edu.wpi.first.wpilibj.command.Subsystem req, edu.wpi.first.wpilibj.PIDController pid, edu.wpi.first.wpilibj.PIDSource source, double target, boolean hold)Constructs a command that moves aPIDControllerto be over a given target, only if the current position is under that target.- Parameters:
req- The subsystem to requirepid- The PID controller to usesource- The PIDSource (encoder, potentiometer, etc.) from which to take the inputtarget- The point to move the PID controller overhold- Whether or not to continue running the PID loop after the target is reached- Returns:
- The newly created
Command
-
release
public static edu.wpi.first.wpilibj.command.Command release(edu.wpi.first.wpilibj.command.Subsystem subsystem)
Create a command which releases control of a subsystem. TheCommandreturned by this method will require the given subsystem, and end instantly. This has the effect of stopping any command using the given subsystem, and of starting the default command, if one exists.- Parameters:
subsystem- The subsystem to release- Returns:
- A command which releases the subsystem
-
-