Class ProfiledTurret

  • All Implemented Interfaces:
    Sendable, Subsystem

    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.
    • 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 angle
        turretPID - PID gain constants for the turret
        minDeadzoneAngle - Robot-relative angle where the turret deadzone starts
        maxDeadzoneAngle - Robot-relative angle where the turret deadzone ends
        epsilon - Turret angle epsilon
    • Method Detail

      • lookAt

        public void lookAt​(Rotation2d angle)
        Description copied from class: TurretBase
        Tell the turret to look at a robot-relative angle
        Specified by:
        lookAt in class TurretBase
        Parameters:
        angle - Robot-relative angle
      • isAligned

        public boolean isAligned()
        Description copied from class: TurretBase
        Get if the turret is aligned with its goal
        Specified by:
        isAligned in class TurretBase
        Returns:
        Is the turret aligned?
      • stop

        public void stop()
        Description copied from class: TurretBase
        Stop the turret
        Specified by:
        stop in class TurretBase