Package frc.robot.shared.commands
Class AbstractSetAndSeekCommandFactory<TSubsystem extends AbstractSetAndSeekSubsystem<?>>
java.lang.Object
frc.robot.shared.commands.AbstractSubsystemCommandFactory<TSubsystem>
frc.robot.shared.commands.AbstractSetAndSeekCommandFactory<TSubsystem>
- Direct Known Subclasses:
HarvesterSubsystemCommandFactory,TurretSubsystemCommandFactory
public class AbstractSetAndSeekCommandFactory<TSubsystem extends AbstractSetAndSeekSubsystem<?>>
extends AbstractSubsystemCommandFactory<TSubsystem>
Command factory for set-and-seek style subsystems that exposes common SysId characterization commands while keeping subsystems free of command
creation.
-
Field Summary
Fields inherited from class frc.robot.shared.commands.AbstractSubsystemCommandFactory
subsystem -
Constructor Summary
ConstructorsModifierConstructorDescriptionprotectedAbstractSetAndSeekCommandFactory(TSubsystem subsystem) Builds a command factory bound to a set-and-seek subsystem. -
Method Summary
Modifier and TypeMethodDescriptionedu.wpi.first.wpilibj2.command.CommandCreates an instant command that resets the motor encoder to the configured initial position and clears all profile state.edu.wpi.first.wpilibj2.command.CommandcreateSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a dynamic SysId characterization command that applies a step voltage in the requested direction.edu.wpi.first.wpilibj2.command.CommandcreateSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds) Creates a dynamic SysId command with a timeout to prevent runaway motion.edu.wpi.first.wpilibj2.command.CommandcreateSysIdDynamicCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a dynamic SysId command with a default timeout (3 seconds) to safeguard robot motion.edu.wpi.first.wpilibj2.command.CommandCreates a full SysId sweep using timing values from the subsystem config.edu.wpi.first.wpilibj2.command.CommandcreateSysIdFullSweepCommand(double delaySeconds, double quasistaticTimeoutSecs, double dynamicTimeoutSecs) Creates a full SysId sweep (quasistatic forward/reverse, dynamic forward/reverse) with optional delays between phases.edu.wpi.first.wpilibj2.command.CommandcreateSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a quasistatic SysId characterization command that ramps voltage slowly in the requested direction.edu.wpi.first.wpilibj2.command.CommandcreateSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds) Creates a quasistatic SysId command with a timeout to prevent runaway motion.edu.wpi.first.wpilibj2.command.CommandcreateSysIdQuasistaticCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a quasistatic SysId command with a default timeout (3 seconds) to safeguard robot motion.Methods inherited from class frc.robot.shared.commands.AbstractSubsystemCommandFactory
getSubsystem
-
Constructor Details
-
AbstractSetAndSeekCommandFactory
Builds a command factory bound to a set-and-seek subsystem.- Parameters:
subsystem- set-and-seek subsystem instance shared by generated commands
-
-
Method Details
-
createResetEncoderCommand
public edu.wpi.first.wpilibj2.command.Command createResetEncoderCommand()Creates an instant command that resets the motor encoder to the configured initial position and clears all profile state.Use this to publish a dashboard-triggerable button so operators can recalibrate a mechanism after manually repositioning it to its starting position (e.g., stowing a harvester arm or centering a turret).
- Returns:
- command that resets the encoder position to the configured initial position
-
createSysIdQuasistaticCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a quasistatic SysId characterization command that ramps voltage slowly in the requested direction.- Parameters:
direction- sweep direction (forward or reverse)- Returns:
- command that runs the quasistatic test until completion
-
createSysIdQuasistaticCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds) Creates a quasistatic SysId command with a timeout to prevent runaway motion.- Parameters:
direction- sweep direction (forward or reverse)timeoutSeconds- maximum duration before the command ends- Returns:
- timed quasistatic SysId command
-
createSysIdQuasistaticCommandWithDefaultTimeout
public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a quasistatic SysId command with a default timeout (3 seconds) to safeguard robot motion.- Parameters:
direction- sweep direction (forward or reverse)- Returns:
- timed quasistatic SysId command
-
createSysIdDynamicCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a dynamic SysId characterization command that applies a step voltage in the requested direction.- Parameters:
direction- sweep direction (forward or reverse)- Returns:
- command that runs the dynamic test until completion
-
createSysIdDynamicCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds) Creates a dynamic SysId command with a timeout to prevent runaway motion.- Parameters:
direction- sweep direction (forward or reverse)timeoutSeconds- maximum duration before the command ends- Returns:
- timed dynamic SysId command
-
createSysIdDynamicCommandWithDefaultTimeout
public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction) Creates a dynamic SysId command with a default timeout (3 seconds) to safeguard robot motion.- Parameters:
direction- sweep direction (forward or reverse)- Returns:
- timed dynamic SysId command
-
createSysIdFullSweepCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdFullSweepCommand()Creates a full SysId sweep using timing values from the subsystem config.Reads
sysIdDelaySeconds,sysIdQuasistaticTimeoutSeconds, andsysIdDynamicTimeoutSecondsfrom the subsystem's configuration so each mechanism can define its own timing without changing bindings code.- Returns:
- command that executes the four standard SysId tests in sequence
-
createSysIdFullSweepCommand
public edu.wpi.first.wpilibj2.command.Command createSysIdFullSweepCommand(double delaySeconds, double quasistaticTimeoutSecs, double dynamicTimeoutSecs) Creates a full SysId sweep (quasistatic forward/reverse, dynamic forward/reverse) with optional delays between phases.- Parameters:
delaySeconds- pause inserted between each phase to let the mechanism settlequasistaticTimeoutSecs- timeout for each quasistatic sweep to prevent runaway motiondynamicTimeoutSecs- timeout for each dynamic sweep to prevent runaway motion- Returns:
- command that executes the four standard SysId tests in sequence
-