From 5eb218f9ffe85988fe82c50d0a09946d3a8a4dc9 Mon Sep 17 00:00:00 2001 From: Programming Laptop 1 <2491nomythic@gmail.com> Date: Sat, 24 Feb 2024 13:16:32 -0600 Subject: [PATCH 1/2] Removed unused imports(Over 90 errors) --- src/main/java/frc/robot/Robot.java | 2 -- src/main/java/frc/robot/RobotContainer.java | 28 ------------------- .../frc/robot/commands/AimRobotMoving.java | 5 ---- .../java/frc/robot/commands/AngleShooter.java | 2 -- .../java/frc/robot/commands/CollectNote.java | 6 ---- .../java/frc/robot/commands/IndexCommand.java | 3 -- .../java/frc/robot/commands/ManualShoot.java | 2 -- .../java/frc/robot/commands/RotateRobot.java | 5 ---- .../frc/robot/commands/autoAimParallel.java | 9 ------ .../commands/climber_commands/AutoClimb.java | 3 -- .../climber_commands/ClimberPullDown.java | 1 - .../frc/robot/commands/goToPose/GoToAmp.java | 1 - .../commands/goToPose/GoToClimbSpot.java | 4 --- .../java/frc/robot/settings/Constants.java | 2 -- .../frc/robot/settings/LimelightValues.java | 3 -- .../subsystems/AngleShooterSubsystem.java | 6 ---- .../java/frc/robot/subsystems/Climber.java | 6 +--- .../robot/subsystems/DrivetrainSubsystem.java | 9 ------ .../robot/subsystems/IndexerSubsystem.java | 6 ---- .../frc/robot/subsystems/IntakeSubsystem.java | 6 +--- .../java/frc/robot/subsystems/Lights.java | 2 -- .../robot/subsystems/ShooterSubsystem.java | 20 ++----------- 22 files changed, 5 insertions(+), 126 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 7562f56a..3cb8978e 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,9 +4,7 @@ package frc.robot; -import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 8ae12889..b58b833a 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -7,56 +7,36 @@ import static frc.robot.settings.Constants.PS4Driver.*; import static frc.robot.settings.Constants.PS4Operator.*; import static frc.robot.settings.Constants.ShooterConstants.LONG_SHOOTING_RPS; -import static frc.robot.settings.Constants.ShooterConstants.SHORT_SHOOTING_RPS; - -import java.nio.file.Path; -import java.time.Instant; -import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; -import org.littletonrobotics.urcl.URCL; - import static frc.robot.settings.Constants.DriveConstants.*; -import com.ctre.phoenix6.SignalLogger; import com.ctre.phoenix6.hardware.Pigeon2; -import com.fasterxml.jackson.core.sym.Name; import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.auto.NamedCommands; -import com.pathplanner.lib.path.PathPlannerPath; import com.pathplanner.lib.util.HolonomicPathFollowerConfig; import com.pathplanner.lib.util.PIDConstants; -import com.pathplanner.lib.util.PathPlannerLogging; import com.pathplanner.lib.util.ReplanningConfig; import frc.robot.commands.AimShooter; import frc.robot.commands.AimRobotMoving; -import frc.robot.commands.IntakeCommand; import frc.robot.commands.CollectNote; import frc.robot.commands.Drive; import frc.robot.commands.DriveTimeCommand; import frc.robot.commands.ConditionalIndexer; -import frc.robot.settings.Constants.Field; import frc.robot.settings.Constants.IndexerConstants; import frc.robot.commands.IndexCommand; import frc.robot.commands.IndicatorLights; import frc.robot.settings.Constants; import frc.robot.settings.Constants.ClimberConstants; -import frc.robot.settings.Constants.DriveConstants; import frc.robot.settings.Constants.IntakeConstants; -import frc.robot.settings.Constants.PathConstants; import frc.robot.settings.Constants.ShooterConstants; import frc.robot.subsystems.AngleShooterSubsystem; import frc.robot.subsystems.Climber; import frc.robot.commands.ManualShoot; -import frc.robot.commands.RotateRobot; -import frc.robot.commands.autoAimParallel; import frc.robot.commands.NamedCommands.initialShot; import frc.robot.commands.NamedCommands.shootNote; import frc.robot.commands.goToPose.GoToAmp; -import frc.robot.commands.goToPose.GoToClimbSpot; -import frc.robot.commands.climber_commands.AutoClimb; -import frc.robot.commands.climber_commands.ClimberPullDown; import frc.robot.subsystems.DrivetrainSubsystem; import frc.robot.subsystems.Lights; import frc.robot.subsystems.IndexerSubsystem; @@ -68,8 +48,6 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; -import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.WaitCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -77,18 +55,12 @@ import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; -import frc.robot.commands.Drive; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.units.Angle; -import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.PS4Controller; import edu.wpi.first.wpilibj.PowerDistribution; -import frc.robot.commands.ManualShoot; import frc.robot.commands.AngleShooter; -import frc.robot.commands.IntakeCommand; import frc.robot.settings.IntakeDirection; diff --git a/src/main/java/frc/robot/commands/AimRobotMoving.java b/src/main/java/frc/robot/commands/AimRobotMoving.java index 901dc6b7..464a6565 100644 --- a/src/main/java/frc/robot/commands/AimRobotMoving.java +++ b/src/main/java/frc/robot/commands/AimRobotMoving.java @@ -1,7 +1,6 @@ package frc.robot.commands; import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.DriverStation; @@ -9,15 +8,11 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.settings.Constants.DriveConstants; -import frc.robot.settings.Constants.Field; import frc.robot.settings.Constants.ShooterConstants; import frc.robot.subsystems.DrivetrainSubsystem; -import static frc.robot.settings.Constants.DriveConstants.*; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kD; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kI; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kP; -import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_SHOOTER_kP; - import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; diff --git a/src/main/java/frc/robot/commands/AngleShooter.java b/src/main/java/frc/robot/commands/AngleShooter.java index be20f9f0..e88b0449 100644 --- a/src/main/java/frc/robot/commands/AngleShooter.java +++ b/src/main/java/frc/robot/commands/AngleShooter.java @@ -6,9 +6,7 @@ import java.util.function.DoubleSupplier; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.ShooterConstants; import frc.robot.subsystems.AngleShooterSubsystem; public class AngleShooter extends Command { diff --git a/src/main/java/frc/robot/commands/CollectNote.java b/src/main/java/frc/robot/commands/CollectNote.java index 61df94e8..728b545b 100644 --- a/src/main/java/frc/robot/commands/CollectNote.java +++ b/src/main/java/frc/robot/commands/CollectNote.java @@ -9,15 +9,9 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; -import edu.wpi.first.wpilibj2.command.WaitCommand; -import frc.robot.settings.Constants.DriveConstants; import frc.robot.settings.Constants.Vision; import frc.robot.settings.LimelightDetectorData; import frc.robot.subsystems.DrivetrainSubsystem; -import static frc.robot.settings.Constants.DriveConstants.*; -import frc.robot.subsystems.IntakeSubsystem; import frc.robot.subsystems.Limelight; public class CollectNote extends Command { diff --git a/src/main/java/frc/robot/commands/IndexCommand.java b/src/main/java/frc/robot/commands/IndexCommand.java index 00780882..2e77696b 100644 --- a/src/main/java/frc/robot/commands/IndexCommand.java +++ b/src/main/java/frc/robot/commands/IndexCommand.java @@ -10,14 +10,11 @@ import java.util.function.DoubleSupplier; import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.PS4Controller; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.DriveConstants; import frc.robot.settings.Constants.Field; import frc.robot.settings.Constants.IndexerConstants; import frc.robot.settings.Constants.ShooterConstants; -import frc.robot.settings.Constants.IntakeConstants; import frc.robot.subsystems.AngleShooterSubsystem; import frc.robot.subsystems.DrivetrainSubsystem; import frc.robot.subsystems.IndexerSubsystem; diff --git a/src/main/java/frc/robot/commands/ManualShoot.java b/src/main/java/frc/robot/commands/ManualShoot.java index 8c800f14..de097c9d 100644 --- a/src/main/java/frc/robot/commands/ManualShoot.java +++ b/src/main/java/frc/robot/commands/ManualShoot.java @@ -4,10 +4,8 @@ package frc.robot.commands; import frc.robot.settings.Constants.IndexerConstants; -import frc.robot.settings.Constants.ShooterConstants; import frc.robot.subsystems.IndexerSubsystem; -import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import edu.wpi.first.wpilibj2.command.Command; diff --git a/src/main/java/frc/robot/commands/RotateRobot.java b/src/main/java/frc/robot/commands/RotateRobot.java index bc9da539..16d26329 100644 --- a/src/main/java/frc/robot/commands/RotateRobot.java +++ b/src/main/java/frc/robot/commands/RotateRobot.java @@ -1,19 +1,14 @@ package frc.robot.commands; import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.Field; import frc.robot.settings.Constants.ShooterConstants; import frc.robot.subsystems.DrivetrainSubsystem; -import static frc.robot.settings.Constants.DriveConstants.*; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kD; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kI; import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_ROBOT_kP; -import static frc.robot.settings.Constants.ShooterConstants.AUTO_AIM_SHOOTER_kP; - import java.util.function.DoubleSupplier; public class RotateRobot extends Command { diff --git a/src/main/java/frc/robot/commands/autoAimParallel.java b/src/main/java/frc/robot/commands/autoAimParallel.java index 5766f955..cf28820d 100644 --- a/src/main/java/frc/robot/commands/autoAimParallel.java +++ b/src/main/java/frc/robot/commands/autoAimParallel.java @@ -4,15 +4,6 @@ package frc.robot.commands; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.PS4Controller; -import edu.wpi.first.wpilibj.DriverStation.Alliance; -import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; -import frc.robot.settings.Constants.Field; -import frc.robot.subsystems.DrivetrainSubsystem; -import frc.robot.subsystems.ShooterSubsystem; -import static frc.robot.settings.Constants.ShooterConstants.*; import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; import frc.robot.subsystems.DrivetrainSubsystem; import frc.robot.subsystems.ShooterSubsystem; diff --git a/src/main/java/frc/robot/commands/climber_commands/AutoClimb.java b/src/main/java/frc/robot/commands/climber_commands/AutoClimb.java index 8546dba0..3522e710 100644 --- a/src/main/java/frc/robot/commands/climber_commands/AutoClimb.java +++ b/src/main/java/frc/robot/commands/climber_commands/AutoClimb.java @@ -4,10 +4,7 @@ package frc.robot.commands.climber_commands; -import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; -import edu.wpi.first.wpilibj2.command.WaitCommand; -import frc.robot.settings.Constants.ClimberConstants; import frc.robot.subsystems.Climber; // NOTE: Consider using this command inline, rather than writing a subclass. For more diff --git a/src/main/java/frc/robot/commands/climber_commands/ClimberPullDown.java b/src/main/java/frc/robot/commands/climber_commands/ClimberPullDown.java index f05c3df4..bc2c1612 100644 --- a/src/main/java/frc/robot/commands/climber_commands/ClimberPullDown.java +++ b/src/main/java/frc/robot/commands/climber_commands/ClimberPullDown.java @@ -5,7 +5,6 @@ package frc.robot.commands.climber_commands; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.ClimberConstants; import frc.robot.subsystems.Climber; public class ClimberPullDown extends Command { diff --git a/src/main/java/frc/robot/commands/goToPose/GoToAmp.java b/src/main/java/frc/robot/commands/goToPose/GoToAmp.java index 52f905cb..25ff8f26 100644 --- a/src/main/java/frc/robot/commands/goToPose/GoToAmp.java +++ b/src/main/java/frc/robot/commands/goToPose/GoToAmp.java @@ -12,7 +12,6 @@ import com.pathplanner.lib.path.PathPlannerPath; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.PathConstants; import frc.robot.subsystems.DrivetrainSubsystem; public class GoToAmp extends Command { diff --git a/src/main/java/frc/robot/commands/goToPose/GoToClimbSpot.java b/src/main/java/frc/robot/commands/goToPose/GoToClimbSpot.java index 82bebb41..06373c62 100644 --- a/src/main/java/frc/robot/commands/goToPose/GoToClimbSpot.java +++ b/src/main/java/frc/robot/commands/goToPose/GoToClimbSpot.java @@ -6,15 +6,11 @@ import static frc.robot.settings.Constants.DriveConstants.DEFAUL_PATH_CONSTRAINTS; -import java.util.function.BooleanSupplier; - import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.path.PathPlannerPath; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.settings.Constants.PathConstants; import frc.robot.subsystems.DrivetrainSubsystem; public class GoToClimbSpot extends Command { diff --git a/src/main/java/frc/robot/settings/Constants.java b/src/main/java/frc/robot/settings/Constants.java index 53ada3d3..6dfd64b0 100644 --- a/src/main/java/frc/robot/settings/Constants.java +++ b/src/main/java/frc/robot/settings/Constants.java @@ -4,8 +4,6 @@ package frc.robot.settings; -import javax.sound.midi.Patch; - import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.configs.Pigeon2Configuration; import com.ctre.phoenix6.configs.TalonFXConfiguration; diff --git a/src/main/java/frc/robot/settings/LimelightValues.java b/src/main/java/frc/robot/settings/LimelightValues.java index 5e577d8c..85025e41 100644 --- a/src/main/java/frc/robot/settings/LimelightValues.java +++ b/src/main/java/frc/robot/settings/LimelightValues.java @@ -11,12 +11,9 @@ import edu.wpi.first.wpilibj.Timer; import frc.robot.LimelightHelpers; import frc.robot.LimelightHelpers.Results; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import static frc.robot.settings.Constants.Vision.MAX_TAG_DISTANCE; import static frc.robot.settings.Constants.Vision.APRILTAG_CLOSENESS; -import edu.wpi.first.networktables.NetworkTableInstance; - /** Add your docs here. */ public class LimelightValues { LimelightHelpers.Results llresults; diff --git a/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java b/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java index 5ea7fcb6..0c6fa71a 100644 --- a/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java @@ -4,10 +4,6 @@ import frc.robot.settings.Constants.ShooterConstants; import java.util.Optional; -import java.util.function.BooleanSupplier; -import java.util.function.DoubleSupplier; - -import com.ctre.phoenix6.hardware.CANcoder; import com.revrobotics.CANSparkMax; import com.revrobotics.SparkAbsoluteEncoder; import com.revrobotics.SparkPIDController; @@ -16,7 +12,6 @@ import com.revrobotics.CANSparkLowLevel.MotorType; import com.revrobotics.SparkAbsoluteEncoder.Type; -import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Translation2d; @@ -24,7 +19,6 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; import static frc.robot.settings.Constants.ShooterConstants.*; import static frc.robot.settings.Constants.LOOPS_VALID_FOR_SHOT; diff --git a/src/main/java/frc/robot/subsystems/Climber.java b/src/main/java/frc/robot/subsystems/Climber.java index 587f51c9..c245a090 100644 --- a/src/main/java/frc/robot/subsystems/Climber.java +++ b/src/main/java/frc/robot/subsystems/Climber.java @@ -4,18 +4,14 @@ package frc.robot.subsystems; -import com.revrobotics.CANSparkBase; import com.revrobotics.CANSparkMax; import com.revrobotics.RelativeEncoder; import com.revrobotics.SparkLimitSwitch; -import com.revrobotics.SparkPIDController; - import com.revrobotics.SparkRelativeEncoder; -import com.revrobotics.CANSparkBase.ControlType; +import com.revrobotics.SparkRelativeEncoder; import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; import com.revrobotics.SparkLimitSwitch.Type; -import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.settings.Constants.ClimberConstants; diff --git a/src/main/java/frc/robot/subsystems/DrivetrainSubsystem.java b/src/main/java/frc/robot/subsystems/DrivetrainSubsystem.java index 407af1c7..44950239 100644 --- a/src/main/java/frc/robot/subsystems/DrivetrainSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DrivetrainSubsystem.java @@ -20,16 +20,11 @@ import static frc.robot.settings.Constants.DriveConstants.FR_STEER_ENCODER_ID; import static frc.robot.settings.Constants.DriveConstants.FR_STEER_MOTOR_ID; import static frc.robot.settings.Constants.ShooterConstants.OFFSET_MULTIPLIER; -import static frc.robot.settings.Constants.*; - import java.util.Arrays; import java.util.Collections; import java.util.Optional; -import javax.swing.text.html.Option; - import com.ctre.phoenix6.hardware.Pigeon2; -import com.pathplanner.lib.commands.PathPlannerAuto; import com.pathplanner.lib.util.PathPlannerLogging; import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; @@ -48,17 +43,13 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.LimelightHelpers; import frc.robot.commands.AngleShooter; -import frc.robot.commands.Drive; import frc.robot.commands.RotateRobot; import frc.robot.settings.Constants; import frc.robot.settings.LimelightValues; import frc.robot.settings.Constants.CTREConfigs; import frc.robot.settings.Constants.DriveConstants; import frc.robot.settings.Constants.Vision; -import frc.robot.settings.Constants.DriveConstants.Offsets; -import frc.robot.settings.Constants.DriveConstants.Positions; import frc.robot.settings.Constants.Field; import frc.robot.settings.Constants.ShooterConstants; diff --git a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java index ff65a191..537efd39 100644 --- a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java @@ -3,16 +3,10 @@ import com.ctre.phoenix6.configs.CurrentLimitsConfigs; import com.ctre.phoenix6.configs.TalonFXConfigurator; import com.ctre.phoenix6.hardware.TalonFX; -import com.revrobotics.CANSparkMax; import com.revrobotics.SparkAnalogSensor; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.SparkAnalogSensor.Mode; - -import edu.wpi.first.wpilibj.motorcontrol.Talon; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.settings.Constants.IndexerConstants; -import frc.robot.settings.Constants.ShooterConstants; public class IndexerSubsystem extends SubsystemBase { TalonFX m_IndexerMotor; diff --git a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java index cd91ef57..5987dcaf 100644 --- a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -5,12 +5,8 @@ package frc.robot.subsystems; import com.revrobotics.CANSparkMax; - import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkAnalogSensor; + import com.revrobotics.SparkAnalogSensor; import com.revrobotics.SparkAnalogSensor.Mode; -import com.revrobotics.SparkPIDController; - import com.revrobotics.SparkRelativeEncoder; - import com.revrobotics.CANSparkBase.ControlType; import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; diff --git a/src/main/java/frc/robot/subsystems/Lights.java b/src/main/java/frc/robot/subsystems/Lights.java index b32a9afc..0d644b76 100644 --- a/src/main/java/frc/robot/subsystems/Lights.java +++ b/src/main/java/frc/robot/subsystems/Lights.java @@ -6,8 +6,6 @@ import edu.wpi.first.wpilibj.AddressableLED; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj.AddressableLEDBuffer; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj.util.Color; public class Lights extends SubsystemBase { /** Creates a new SubsystemLights. */ diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index c2a10719..733b7a8b 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -3,34 +3,20 @@ // the WPILib BSD license file in the root directory of this project. package frc.robot.subsystems; - import com.ctre.phoenix6.configs.ClosedLoopGeneralConfigs; -import com.ctre.phoenix6.configs.CurrentLimitsConfigs; + import com.ctre.phoenix6.configs.CurrentLimitsConfigs; import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.configs.TalonFXConfigurator; -import com.ctre.phoenix6.controls.ControlRequest; import com.ctre.phoenix6.controls.DutyCycleOut; -import com.ctre.phoenix6.controls.Follower; import com.ctre.phoenix6.controls.VelocityDutyCycle; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; -import com.revrobotics.CANSparkMax; - import com.revrobotics.RelativeEncoder; - import com.revrobotics.SparkPIDController; - import com.revrobotics.SparkRelativeEncoder; - import com.revrobotics.CANSparkBase.ControlType; -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.SparkAbsoluteEncoder.Type; - -import frc.robot.commands.AngleShooter; +import com.revrobotics.RelativeEncoder; + import frc.robot.commands.AngleShooter; import frc.robot.commands.RotateRobot; import frc.robot.settings.Constants; import frc.robot.settings.Constants.ShooterConstants; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import static frc.robot.settings.Constants.ShooterConstants.*; -import static frc.robot.settings.Constants.*; public class ShooterSubsystem extends SubsystemBase { TalonFX shooterR; From c37b6432580c53254556e1a9685adb0377a76791 Mon Sep 17 00:00:00 2001 From: Programming Laptop 1 <2491nomythic@gmail.com> Date: Sat, 24 Feb 2024 13:25:33 -0600 Subject: [PATCH 2/2] Removed/Commented unused variables(and bugs/imports) --- src/main/java/frc/robot/RobotContainer.java | 18 +++--------------- .../java/frc/robot/commands/IndexCommand.java | 6 ------ .../commands/NamedCommands/initialShot.java | 6 +++--- .../subsystems/AngleShooterSubsystem.java | 3 ++- .../frc/robot/subsystems/ShooterSubsystem.java | 8 ++++---- .../frc/robot/subsystems/SwerveModule.java | 4 ---- 6 files changed, 12 insertions(+), 33 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index b58b833a..0c563745 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -5,13 +5,9 @@ package frc.robot; import static frc.robot.settings.Constants.PS4Driver.*; -import static frc.robot.settings.Constants.PS4Operator.*; import static frc.robot.settings.Constants.ShooterConstants.LONG_SHOOTING_RPS; -import java.util.function.DoubleSupplier; - import static frc.robot.settings.Constants.DriveConstants.*; -import com.ctre.phoenix6.hardware.Pigeon2; import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.auto.NamedCommands; import com.pathplanner.lib.util.HolonomicPathFollowerConfig; @@ -61,7 +57,6 @@ import edu.wpi.first.wpilibj.PS4Controller; import edu.wpi.first.wpilibj.PowerDistribution; import frc.robot.commands.AngleShooter; -import frc.robot.settings.IntakeDirection; /** @@ -80,7 +75,7 @@ public class RobotContainer { private final boolean climberExists = Preferences.getBoolean("Climber", true); private final boolean lightsExist = Preferences.getBoolean("Lights", true); private final boolean indexerExists = Preferences.getBoolean("Indexer", true); - private final boolean autosExist = Preferences.getBoolean("Autos", true); + //private final boolean autosExist = Preferences.getBoolean("Autos", true); private final boolean useDetectorLimelight = Preferences.getBoolean("Detector Limelight", true); private DrivetrainSubsystem driveTrain; @@ -91,16 +86,13 @@ public class RobotContainer { private Climber climber; private Lights lights; private PS4Controller driverController; - private PS4Controller operatorController; + //private PS4Controller operatorController; private Limelight limelight; - private IntakeDirection iDirection; - private Pigeon2 pigeon; private IndexCommand defaulNoteHandlingCommand; private IndexerSubsystem indexer; private AimShooter defaultShooterAngleCommand; private SendableChooser climbSpotChooser; private SendableChooser autoChooser; - private DoubleSupplier angleSup; private PowerDistribution PDP; // Replace with CommandPS4Controller or CommandJoystick if needed @@ -125,8 +117,7 @@ public RobotContainer() { // SignalLogger.setPath("/media/sda1/ctre-logs/"); // SignalLogger.start(); driverController = new PS4Controller(DRIVE_CONTROLLER_ID); - operatorController = new PS4Controller(OPERATOR_CONTROLLER_ID); - pigeon = new Pigeon2(DRIVETRAIN_PIGEON_ID); + //operatorController = new PS4Controller(OPERATOR_CONTROLLER_ID); PDP = new PowerDistribution(1, ModuleType.kRev); // = new PathPlannerPath(null, DEFAUL_PATH_CONSTRAINTS, null, climberExists); @@ -342,9 +333,6 @@ private double modifyAxis(double value, double deadband) { return value; } - private double getAmpAngle() { - return Constants.Field.AMPLIFIER_ANGLE; - } private void configureDriveTrain() { AutoBuilder.configureHolonomic( driveTrain::getPose, // Pose2d supplier diff --git a/src/main/java/frc/robot/commands/IndexCommand.java b/src/main/java/frc/robot/commands/IndexCommand.java index 2e77696b..90be7a18 100644 --- a/src/main/java/frc/robot/commands/IndexCommand.java +++ b/src/main/java/frc/robot/commands/IndexCommand.java @@ -38,9 +38,6 @@ public class IndexCommand extends Command { AngleShooterSubsystem angleShooterSubsytem; boolean auto; double runsEmpty = 0; - BooleanSupplier SubwooferSupplier1; - BooleanSupplier SubwooferSupplier2; - BooleanSupplier SubwooferSupplier3; /** Creates a new IndexCommand. */ public IndexCommand(IndexerSubsystem m_IndexerSubsystem, BooleanSupplier shootIfReadySupplier, BooleanSupplier revUpSupplier, ShooterSubsystem shooter, IntakeSubsystem intake, DrivetrainSubsystem drivetrain, AngleShooterSubsystem angleShooterSubsystem, BooleanSupplier humanPlaySupplier, DoubleSupplier ampSupplier) { @@ -53,9 +50,6 @@ public IndexCommand(IndexerSubsystem m_IndexerSubsystem, BooleanSupplier shootIf this.ampSupplier = ampSupplier; this.angleShooterSubsytem = angleShooterSubsystem; this.humanPlayerSupplier = humanPlaySupplier;//R1 - this.SubwooferSupplier1 = SubwooferSupplier1; - this.SubwooferSupplier2 = SubwooferSupplier2; - this.SubwooferSupplier3 = SubwooferSupplier3; SmartDashboard.putNumber("amp RPS", AMP_RPS); SmartDashboard.putNumber("indexer amp speed", IndexerConstants.INDEXER_AMP_SPEED); SmartDashboard.putNumber("amp angle", Field.AMPLIFIER_ANGLE); diff --git a/src/main/java/frc/robot/commands/NamedCommands/initialShot.java b/src/main/java/frc/robot/commands/NamedCommands/initialShot.java index 55be77ab..9454ada7 100644 --- a/src/main/java/frc/robot/commands/NamedCommands/initialShot.java +++ b/src/main/java/frc/robot/commands/NamedCommands/initialShot.java @@ -14,13 +14,13 @@ public class initialShot extends Command { ShooterSubsystem shooter; IndexerSubsystem indexer; Timer timer; - double revtime; + double revTime; double shootTime; /** Creates a new shootThing. */ public initialShot(ShooterSubsystem shooter, IndexerSubsystem indexer, double revTime, double shootTime) { this.indexer = indexer; this.shooter = shooter; - this.revtime = revtime; + this.revTime = revTime; this.shootTime = shootTime; timer = new Timer(); addRequirements(shooter, indexer); @@ -37,7 +37,7 @@ public void initialize() { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(timer.get()>revtime) { + if(timer.get()>revTime) { indexer.on(); } } diff --git a/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java b/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java index 0c6fa71a..44616774 100644 --- a/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/AngleShooterSubsystem.java @@ -133,8 +133,9 @@ public double calculateSpeakerAngle() { } SmartDashboard.putNumber("desired shooter angle", desiredShooterAngle); - double differenceAngle = (desiredShooterAngle - this.getShooterAngle()); + speakerDistGlobal = offsetSpeakerdist; + // double differenceAngle = (desiredShooterAngle - this.getShooterAngle()); // SmartDashboard.putNumber("differenceAngleShooter", differenceAngle); return desiredShooterAngle; diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 733b7a8b..bad142a8 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -87,11 +87,11 @@ public ShooterSubsystem(double runSpeed) { double p = SmartDashboard.getNumber("P Gain", 0); double i = SmartDashboard.getNumber("I Gain", 0); double d = SmartDashboard.getNumber("D Gain", 0); - double iz = SmartDashboard.getNumber("I Zone", 0); + //double iz = SmartDashboard.getNumber("I Zone", 0); double ff = SmartDashboard.getNumber("Feed Forward", 0); - double max = SmartDashboard.getNumber("Max Output", 0); - double min = SmartDashboard.getNumber("Min Output", 0); - double ve = SmartDashboard.getNumber("Set Velocity", 0); + //double max = SmartDashboard.getNumber("Max Output", 0); + //double min = SmartDashboard.getNumber("Min Output", 0); + //double ve = SmartDashboard.getNumber("Set Velocity", 0); if((p != kP)) {PIDconfigs.kP = p; kP = p; } diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java index 0e3b5a35..a71614f4 100644 --- a/src/main/java/frc/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -6,10 +6,8 @@ import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.CoastOut; import com.ctre.phoenix6.controls.NeutralOut; import com.ctre.phoenix6.controls.PositionDutyCycle; -import com.ctre.phoenix6.controls.StaticBrake; import com.ctre.phoenix6.controls.VelocityDutyCycle; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.TalonFX; @@ -41,8 +39,6 @@ public class SwerveModule { private VelocityDutyCycle m_driveControl = new VelocityDutyCycle(0); private PositionDutyCycle m_steerControl = new PositionDutyCycle(0); - private CoastOut m_coastControl = new CoastOut(); - private StaticBrake m_brakeControl = new StaticBrake(); private NeutralOut m_neutralControl = new NeutralOut(); /**