Package tagalong.commands.base
Class PivotToDynamicAbsoluteCmd<T extends TagalongSubsystemBase & PivotAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.PivotToDynamicAbsoluteCmd<T>
- All Implemented Interfaces:
- Sendable
public class PivotToDynamicAbsoluteCmd<T extends TagalongSubsystemBase & PivotAugment>
extends TagalongCommand
Command that continuously and optimally moves the pivot towards the supplied goal rotation
- 
Nested Class SummaryNested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.CommandCommand.InterruptionBehavior
- 
Constructor SummaryConstructorsConstructorDescriptionPivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position.PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) Continuously move to the double suppliers target position.
- 
Method SummaryMethods inherited from class tagalong.commands.TagalongCommandanonymizeMethods inherited from class edu.wpi.first.wpilibj2.command.CommandaddRequirements, addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineFor, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, runsWhenDisabled, schedule, setName, setSubsystem, unless, until, withDeadline, withInterruptBehavior, withName, withTimeout, withTimeout
- 
Constructor Details- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- id- Integer ID of the pivot microsystem inside the Tagalong Subsystem
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes
- maxVelocityRPS- Maximum velocity for the pivot during this command
- startSupplier- BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
 
- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes
- maxVelocityRPS- Maximum velocity for the pivot during this command
- startSupplier- BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
 
- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- id- Integer ID of the pivot microsystem inside the Tagalong Subsystem
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes
- maxVelocityRPS- Maximum velocity for the pivot during this command
 
- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes
- maxVelocityRPS- Maximum velocity for the pivot during this command
 
- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- id- Integer ID of the pivot microsystem inside the Tagalong Subsystem
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes
 
- 
PivotToDynamicAbsoluteCmdpublic PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
- holdPositionAfter- If the pivot should hold position when the command completes command
 
- 
PivotToDynamicAbsoluteCmdContinuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- id- Integer ID of the pivot microsystem inside the Tagalong Subsystem
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
 
- 
PivotToDynamicAbsoluteCmdContinuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
- pivot- Tagalong Subsystem containing an pivot microsystem
- goalSupplierRot- DoubleSupplier for the pivot rotation
 
 
- 
- 
Method Details- 
initialize- Overrides:
- initializein class- Command
 
- 
execute
- 
end
- 
isFinished- Overrides:
- isFinishedin class- Command
 
 
-