Class ProfiledTurret
- java.lang.Object
 - 
- edu.wpi.first.wpilibj2.command.SubsystemBase
 - 
- ca.retrylife.frc.templates.turrets.TurretBase
 - 
- ca.retrylife.frc.templates.turrets.ProfiledTurret
 
 
 
 
- 
public class ProfiledTurret extends TurretBase
The ProfiledTurret class is to be used to control a turret of any kind. This specifically is designed for turrets that do not support infinite rotation, and will use motion profiling to plan the quickest path around a turret's deadband zone. 
- 
- 
Field Summary
- 
Fields inherited from class ca.retrylife.frc.templates.turrets.TurretBase
deadzone 
 - 
 
- 
Constructor Summary
Constructors Constructor Description ProfiledTurret(SpeedController motor, java.util.function.Supplier<Rotation2d> turretAngleSupplier, ProfiledPIDController turretPID, Rotation2d minDeadzoneAngle, Rotation2d maxDeadzoneAngle, Rotation2d epsilon)Create a ProfiledTurret 
- 
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description booleanisAligned()Get if the turret is aligned with its goalvoidlookAt(Rotation2d angle)Tell the turret to look at a robot-relative anglevoidperiodic()voidstop()Stop the turret- 
Methods inherited from class ca.retrylife.frc.templates.turrets.TurretBase
findDistanceFromAToB, lookAt 
- 
Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem 
- 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait 
- 
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
getCurrentCommand, getDefaultCommand, register, setDefaultCommand, simulationPeriodic 
 - 
 
 - 
 
- 
- 
Constructor Detail
- 
ProfiledTurret
public ProfiledTurret(SpeedController motor, java.util.function.Supplier<Rotation2d> turretAngleSupplier, ProfiledPIDController turretPID, Rotation2d minDeadzoneAngle, Rotation2d maxDeadzoneAngle, Rotation2d epsilon)
Create a ProfiledTurret- Parameters:
 motor- Turret motor controller(s)turretAngleSupplier- Supplier of the turret's robot-relative angleturretPID- PID gain constants for the turretminDeadzoneAngle- Robot-relative angle where the turret deadzone startsmaxDeadzoneAngle- Robot-relative angle where the turret deadzone endsepsilon- Turret angle epsilon
 
 - 
 
- 
Method Detail
- 
periodic
public void periodic()
- Specified by:
 periodicin interfaceSubsystem- Specified by:
 periodicin classTurretBase
 
- 
lookAt
public void lookAt(Rotation2d angle)
Description copied from class:TurretBaseTell the turret to look at a robot-relative angle- Specified by:
 lookAtin classTurretBase- Parameters:
 angle- Robot-relative angle
 
- 
isAligned
public boolean isAligned()
Description copied from class:TurretBaseGet if the turret is aligned with its goal- Specified by:
 isAlignedin classTurretBase- Returns:
 - Is the turret aligned?
 
 
- 
stop
public void stop()
Description copied from class:TurretBaseStop the turret- Specified by:
 stopin classTurretBase
 
 - 
 
 -