From e10c88b05878fbfa63e5418b3c22fc7670673ee7 Mon Sep 17 00:00:00 2001 From: ShmayaR Date: Thu, 25 Dec 2025 13:06:51 +0200 Subject: [PATCH 01/13] added operator constants class --- src/main/java/frc/robot/RobotContainer.java | 20 ++++++++++++++----- .../robot/constants/OperatorConstants.java | 8 ++++++++ 2 files changed, 23 insertions(+), 5 deletions(-) create mode 100644 src/main/java/frc/robot/constants/OperatorConstants.java diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 50f185a..1054f46 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -10,14 +10,15 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.shooter.Shooter; +import frc.robot.subsystems.shooter.ShooterCommands; +import frc.robot.subsystems.shooter.ShooterConstants; import frc.robot.subsystems.tank.Tank; import frc.robot.subsystems.tank.TankCommands; import frc.robot.subsystems.transporter.Transporter; -import frc.robot.commands.*; public class RobotContainer { public static final Intake INTAKE = new Intake(); - public static Shooter SHOOTER = new Shooter(); + public static Shooter SHOOTER = new Shooter(); public static Transporter TRANSPORTER = new Transporter(); public static final Tank TANK = new Tank(); private static final CommandXboxController DRIVER_CONTROLLER = new CommandXboxController(0); @@ -26,7 +27,7 @@ public RobotContainer() { configureBindings(); TANK.setDefaultCommand( TankCommands.getArcadeDriveCommand( - () -> -DRIVER_CONTROLLER.getLeftY(), + DRIVER_CONTROLLER::getLeftY, DRIVER_CONTROLLER::getRightX ) ); @@ -39,10 +40,19 @@ public RobotContainer() { IntakeAndTransportTennisBallCommand.EjectTennisBall() );*/ } - + private void configureBindings() { + bindDefaultCommands(); + bindControllerCommands(); + } + + private void bindDefaultCommands() { } - + + private void bindControllerCommands() { + } + + public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); } diff --git a/src/main/java/frc/robot/constants/OperatorConstants.java b/src/main/java/frc/robot/constants/OperatorConstants.java new file mode 100644 index 0000000..ca18cb8 --- /dev/null +++ b/src/main/java/frc/robot/constants/OperatorConstants.java @@ -0,0 +1,8 @@ +package frc.robot.constants; + +import edu.wpi.first.wpilibj.XboxController; + +public class OperatorConstants { + private static final int DRIVER_CONTROLLER_PORT = 0; + public static final XboxController DRIVER_CONTROLLER = new XboxController(DRIVER_CONTROLLER_PORT); +} From 3a02a270194676a955a6d94ed002eb475692df39 Mon Sep 17 00:00:00 2001 From: ShmayaR Date: Thu, 25 Dec 2025 13:15:12 +0200 Subject: [PATCH 02/13] fixed operator constants --- src/main/java/frc/robot/RobotContainer.java | 1 + src/main/java/frc/robot/constants/OperatorConstants.java | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1054f46..0c2a6f9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,6 +8,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.constants.OperatorConstants; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.shooter.Shooter; import frc.robot.subsystems.shooter.ShooterCommands; diff --git a/src/main/java/frc/robot/constants/OperatorConstants.java b/src/main/java/frc/robot/constants/OperatorConstants.java index ca18cb8..a71c2c0 100644 --- a/src/main/java/frc/robot/constants/OperatorConstants.java +++ b/src/main/java/frc/robot/constants/OperatorConstants.java @@ -1,8 +1,8 @@ package frc.robot.constants; -import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; public class OperatorConstants { private static final int DRIVER_CONTROLLER_PORT = 0; - public static final XboxController DRIVER_CONTROLLER = new XboxController(DRIVER_CONTROLLER_PORT); + public static final CommandXboxController DRIVER_CONTROLLER = new CommandXboxController(DRIVER_CONTROLLER_PORT); } From 70411ba43623d2b6f558e853117a179a77b6259a Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 13:15:38 +0200 Subject: [PATCH 03/13] defult commands --- src/main/java/frc/robot/RobotContainer.java | 22 ++++++++++++++------- 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1054f46..ac94495 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -7,6 +7,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.shooter.Shooter; @@ -25,13 +26,6 @@ public class RobotContainer { public RobotContainer() { configureBindings(); - TANK.setDefaultCommand( - TankCommands.getArcadeDriveCommand( - DRIVER_CONTROLLER::getLeftY, - DRIVER_CONTROLLER::getRightX - ) - ); - /*DRIVER_CONTROLLER.rightTrigger().whileTrue( IntakeAndTransportTennisBallCommand.CollectTennisBall() ); @@ -47,6 +41,20 @@ private void configureBindings() { } private void bindDefaultCommands() { + TANK.setDefaultCommand( + TankCommands.getArcadeDriveCommand( + DRIVER_CONTROLLER::getLeftY, + DRIVER_CONTROLLER::getRightX + ) + ); + + SHOOTER.setDefaultCommand( + ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST) + ); + + INTAKE.setDefaultCommand( + InstantCommand + ) } private void bindControllerCommands() { From 0bb85c70413031712a8ca1f8deb82aae9fe4cfc8 Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 13:17:27 +0200 Subject: [PATCH 04/13] Intake default command --- src/main/java/frc/robot/RobotContainer.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 5dc6441..000cd8b 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -11,6 +11,8 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.constants.OperatorConstants; import frc.robot.subsystems.intake.Intake; +import frc.robot.subsystems.intake.IntakeCommands; +import frc.robot.subsystems.intake.IntakeConstants; import frc.robot.subsystems.shooter.Shooter; import frc.robot.subsystems.shooter.ShooterCommands; import frc.robot.subsystems.shooter.ShooterConstants; @@ -54,7 +56,7 @@ private void bindDefaultCommands() { ); INTAKE.setDefaultCommand( - InstantCommand + IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST) ) } From 2c1ca485e4449eff63e748536ca764f44d74dfd0 Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 13:19:10 +0200 Subject: [PATCH 05/13] set default command --- src/main/java/frc/robot/RobotContainer.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 000cd8b..a468a64 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -19,6 +19,8 @@ import frc.robot.subsystems.tank.Tank; import frc.robot.subsystems.tank.TankCommands; import frc.robot.subsystems.transporter.Transporter; +import frc.robot.subsystems.transporter.TransporterCommands; +import frc.robot.subsystems.transporter.TransporterConstants; public class RobotContainer { public static final Intake INTAKE = new Intake(); @@ -51,13 +53,11 @@ private void bindDefaultCommands() { ) ); - SHOOTER.setDefaultCommand( - ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST) - ); + SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); + + INTAKE.setDefaultCommand(IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST)); - INTAKE.setDefaultCommand( - IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST) - ) + TRANSPORTER.setDefaultCommand(TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.REST)); } private void bindControllerCommands() { From 9575052b00c4b2278164385fcda7746a7a809918 Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 13:29:48 +0200 Subject: [PATCH 06/13] TANK general command --- src/main/java/frc/robot/RobotContainer.java | 21 +++---------------- .../frc/robot/commands/GeneralCommands.java | 15 +++++++++++++ 2 files changed, 18 insertions(+), 18 deletions(-) create mode 100644 src/main/java/frc/robot/commands/GeneralCommands.java diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index a468a64..f4f55f5 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -9,6 +9,7 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.commands.GeneralCommands; import frc.robot.constants.OperatorConstants; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.intake.IntakeCommands; @@ -27,17 +28,9 @@ public class RobotContainer { public static Shooter SHOOTER = new Shooter(); public static Transporter TRANSPORTER = new Transporter(); public static final Tank TANK = new Tank(); - private static final CommandXboxController DRIVER_CONTROLLER = new CommandXboxController(0); public RobotContainer() { configureBindings(); - /*DRIVER_CONTROLLER.rightTrigger().whileTrue( - IntakeAndTransportTennisBallCommand.CollectTennisBall() - ); - - DRIVER_CONTROLLER.rightBumper().whileTrue( - IntakeAndTransportTennisBallCommand.EjectTennisBall() - );*/ } private void configureBindings() { @@ -46,17 +39,9 @@ private void configureBindings() { } private void bindDefaultCommands() { - TANK.setDefaultCommand( - TankCommands.getArcadeDriveCommand( - DRIVER_CONTROLLER::getLeftY, - DRIVER_CONTROLLER::getRightX - ) - ); - - SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); - + TANK.setDefaultCommand(GeneralCommands.getTankDefaultCommand()); INTAKE.setDefaultCommand(IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST)); - + SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); TRANSPORTER.setDefaultCommand(TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.REST)); } diff --git a/src/main/java/frc/robot/commands/GeneralCommands.java b/src/main/java/frc/robot/commands/GeneralCommands.java new file mode 100644 index 0000000..c81cb51 --- /dev/null +++ b/src/main/java/frc/robot/commands/GeneralCommands.java @@ -0,0 +1,15 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.constants.OperatorConstants; +import frc.robot.subsystems.tank.TankCommands; + +public class GeneralCommands { + + public static Command getTankDefaultCommand(){ + return TankCommands.getArcadeDriveCommand( + OperatorConstants.DRIVER_CONTROLLER::getLeftY, + OperatorConstants.DRIVER_CONTROLLER::getRightX + ); + } +} \ No newline at end of file From 1fc63b051b66d85a529121da3fb5bf31f7b93f16 Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 13:43:56 +0200 Subject: [PATCH 07/13] CollectionShootingCommand --- .../frc/robot/commands/CollectWhileShoot.java | 20 +++++++++++++++++++ .../subsystems/intake/IntakeConstants.java | 6 +++--- .../transporter/TransporterConstants.java | 4 ++-- 3 files changed, 25 insertions(+), 5 deletions(-) create mode 100644 src/main/java/frc/robot/commands/CollectWhileShoot.java diff --git a/src/main/java/frc/robot/commands/CollectWhileShoot.java b/src/main/java/frc/robot/commands/CollectWhileShoot.java new file mode 100644 index 0000000..dabda30 --- /dev/null +++ b/src/main/java/frc/robot/commands/CollectWhileShoot.java @@ -0,0 +1,20 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; +import frc.robot.subsystems.intake.IntakeCommands; +import frc.robot.subsystems.intake.IntakeConstants; +import frc.robot.subsystems.shooter.ShooterCommands; +import frc.robot.subsystems.shooter.ShooterConstants; +import frc.robot.subsystems.transporter.TransporterCommands; +import frc.robot.subsystems.transporter.TransporterConstants; + +public class CollectWhileShoot { + public static Command CollectingAndShootingCommand(){ + return new ParallelCommandGroup( + ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.SHOOT), + IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.COLLECT_STATE), + TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) + ); + } +} diff --git a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java index 08e612e..f6df248 100644 --- a/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/intake/IntakeConstants.java @@ -42,9 +42,9 @@ private static void configureFollowerMotor() { } public enum IntakeState { - COLLECT_STATE(-12.0), - EJECT_STATE(12.0), - REST(0.0); + COLLECT_STATE(3), + EJECT_STATE(-3), + REST(0); public final double targetVoltage; diff --git a/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java b/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java index 23f498f..0be0566 100644 --- a/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java +++ b/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java @@ -43,8 +43,8 @@ private static void configureFollowerMotor() { } public enum TransporterState{ - COLLECT_STATE(5), - EJECT_STAGE(-4), + COLLECT_STATE(3), + EJECT_STAGE(-3), REST(0); public final double targetVoltage; From 6e978a00e0ce00313818b46b859819bc9ef89855 Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 14:01:46 +0200 Subject: [PATCH 08/13] triggers --- src/main/java/frc/robot/constants/OperatorConstants.java | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/constants/OperatorConstants.java b/src/main/java/frc/robot/constants/OperatorConstants.java index a71c2c0..5ee2055 100644 --- a/src/main/java/frc/robot/constants/OperatorConstants.java +++ b/src/main/java/frc/robot/constants/OperatorConstants.java @@ -1,8 +1,13 @@ package frc.robot.constants; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; public class OperatorConstants { private static final int DRIVER_CONTROLLER_PORT = 0; public static final CommandXboxController DRIVER_CONTROLLER = new CommandXboxController(DRIVER_CONTROLLER_PORT); -} + public static final Trigger + SHOOT = DRIVER_CONTROLLER.rightTrigger().and(DRIVER_CONTROLLER.leftTrigger().negate()), + COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightTrigger().negate()), + SHOOT_WHILE_COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightTrigger()); +} \ No newline at end of file From a2ba9e1ae5deeacdab990b51a4571d72b98886bc Mon Sep 17 00:00:00 2001 From: 0xRSAvoid Date: Thu, 25 Dec 2025 23:29:51 +0200 Subject: [PATCH 09/13] rightBumper instand of right trigger --- src/main/java/frc/robot/constants/OperatorConstants.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/constants/OperatorConstants.java b/src/main/java/frc/robot/constants/OperatorConstants.java index 5ee2055..358e3c9 100644 --- a/src/main/java/frc/robot/constants/OperatorConstants.java +++ b/src/main/java/frc/robot/constants/OperatorConstants.java @@ -7,7 +7,7 @@ public class OperatorConstants { private static final int DRIVER_CONTROLLER_PORT = 0; public static final CommandXboxController DRIVER_CONTROLLER = new CommandXboxController(DRIVER_CONTROLLER_PORT); public static final Trigger - SHOOT = DRIVER_CONTROLLER.rightTrigger().and(DRIVER_CONTROLLER.leftTrigger().negate()), - COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightTrigger().negate()), - SHOOT_WHILE_COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightTrigger()); + SHOOT = DRIVER_CONTROLLER.rightBumper().and(DRIVER_CONTROLLER.leftTrigger().negate()), + COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightBumper().negate()), + SHOOT_WHILE_COLLECT = DRIVER_CONTROLLER.leftTrigger().and(DRIVER_CONTROLLER.rightBumper().negate()); } \ No newline at end of file From b4afc815df0de2f7f71c75f22ad2b19930c7bdc6 Mon Sep 17 00:00:00 2001 From: ShmayaR Date: Fri, 26 Dec 2025 02:02:48 +0200 Subject: [PATCH 10/13] added shift mode --- .../frc/robot/commands/CommandConstants.java | 35 +++++++++++++++++++ .../frc/robot/commands/GeneralCommands.java | 6 ++-- 2 files changed, 38 insertions(+), 3 deletions(-) create mode 100644 src/main/java/frc/robot/commands/CommandConstants.java diff --git a/src/main/java/frc/robot/commands/CommandConstants.java b/src/main/java/frc/robot/commands/CommandConstants.java new file mode 100644 index 0000000..95e57f0 --- /dev/null +++ b/src/main/java/frc/robot/commands/CommandConstants.java @@ -0,0 +1,35 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.constants.OperatorConstants; +import frc.robot.subsystems.tank.TankCommands; + +public class CommandConstants { + private static final CommandXboxController DRIVER_CONTROLLER = OperatorConstants.DRIVER_CONTROLLER; + private static final double + MINIMUM_DRIVE_SHIFT_POWER = 0.30, + MINIMUM_ROTATION_SHIFT_POWER = 0.4; + + public static final Command + DRIVE_TANK_COMMAND = TankCommands.getArcadeDriveCommand( + () -> calculateDriveStickAxisValue(DRIVER_CONTROLLER.getLeftY()), + () -> calculateRotationStickAxisValue(DRIVER_CONTROLLER.getRightX()) + ); + + public static double calculateDriveStickAxisValue(double axisValue) { + return axisValue / calculateShiftModeValue(MINIMUM_DRIVE_SHIFT_POWER); + } + + public static double calculateRotationStickAxisValue(double axisValue) { + return axisValue / calculateShiftModeValue(MINIMUM_ROTATION_SHIFT_POWER); + } + + public static double calculateShiftModeValue(double minimumPower) { + final double squaredShiftModeValue = Math.sqrt(DRIVER_CONTROLLER.getRightTriggerAxis()); + final double minimumShiftValueCoefficient = 1 - (1 / minimumPower); + + return 1 - squaredShiftModeValue * minimumShiftValueCoefficient; + } +} + diff --git a/src/main/java/frc/robot/commands/GeneralCommands.java b/src/main/java/frc/robot/commands/GeneralCommands.java index c81cb51..98afceb 100644 --- a/src/main/java/frc/robot/commands/GeneralCommands.java +++ b/src/main/java/frc/robot/commands/GeneralCommands.java @@ -6,10 +6,10 @@ public class GeneralCommands { - public static Command getTankDefaultCommand(){ + public static Command getTankDefaultCommand() { return TankCommands.getArcadeDriveCommand( - OperatorConstants.DRIVER_CONTROLLER::getLeftY, - OperatorConstants.DRIVER_CONTROLLER::getRightX + () -> CommandConstants.calculateDriveStickAxisValue(OperatorConstants.DRIVER_CONTROLLER.getLeftY()), + () -> CommandConstants.calculateDriveStickAxisValue(OperatorConstants.DRIVER_CONTROLLER.getRightX()) ); } } \ No newline at end of file From d420f9fb970bf1127c962162dfe87379bf0f34db Mon Sep 17 00:00:00 2001 From: ShmayaR Date: Fri, 26 Dec 2025 04:08:25 +0200 Subject: [PATCH 11/13] added spark max shooter --- src/main/java/frc/robot/RobotContainer.java | 17 ++--- .../frc/robot/commands/CollectWhileShoot.java | 4 +- .../frc/robot/commands/ShootingCommands.java | 6 +- .../subsystems/shooter/ShooterConstants.java | 9 ++- .../subsystems/sparkShooter/SparkShooter.java | 27 +++++++ .../sparkShooter/SparkShooterCommands.java | 14 ++++ .../sparkShooter/SparkShooterConstants.java | 39 ++++++++++ .../subsystems/transporter/Transporter.java | 4 +- .../transporter/TransporterConstants.java | 45 ++++-------- vendordeps/REVLib.json | 71 +++++++++++++++++++ 10 files changed, 187 insertions(+), 49 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/sparkShooter/SparkShooter.java create mode 100644 src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterCommands.java create mode 100644 src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java create mode 100644 vendordeps/REVLib.json diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index f4f55f5..21b314f 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -7,25 +7,24 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.commands.CollectingCommands; import frc.robot.commands.GeneralCommands; import frc.robot.constants.OperatorConstants; import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.intake.IntakeCommands; import frc.robot.subsystems.intake.IntakeConstants; -import frc.robot.subsystems.shooter.Shooter; -import frc.robot.subsystems.shooter.ShooterCommands; -import frc.robot.subsystems.shooter.ShooterConstants; +import frc.robot.subsystems.sparkShooter.SparkShooter; +import frc.robot.subsystems.sparkShooter.SparkShooterCommands; +import frc.robot.subsystems.sparkShooter.SparkShooterConstants; import frc.robot.subsystems.tank.Tank; -import frc.robot.subsystems.tank.TankCommands; import frc.robot.subsystems.transporter.Transporter; import frc.robot.subsystems.transporter.TransporterCommands; import frc.robot.subsystems.transporter.TransporterConstants; public class RobotContainer { public static final Intake INTAKE = new Intake(); - public static Shooter SHOOTER = new Shooter(); + // public static Shooter SHOOTER = new Shooter(); + public static SparkShooter SPARK_SHOOTER = new SparkShooter(); public static Transporter TRANSPORTER = new Transporter(); public static final Tank TANK = new Tank(); @@ -41,11 +40,13 @@ private void configureBindings() { private void bindDefaultCommands() { TANK.setDefaultCommand(GeneralCommands.getTankDefaultCommand()); INTAKE.setDefaultCommand(IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST)); - SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); + // SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); + SPARK_SHOOTER.setDefaultCommand(SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.REST)); TRANSPORTER.setDefaultCommand(TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.REST)); } private void bindControllerCommands() { + OperatorConstants.COLLECT.whileTrue(CollectingCommands.CollectTennisBall()); } diff --git a/src/main/java/frc/robot/commands/CollectWhileShoot.java b/src/main/java/frc/robot/commands/CollectWhileShoot.java index dabda30..291d210 100644 --- a/src/main/java/frc/robot/commands/CollectWhileShoot.java +++ b/src/main/java/frc/robot/commands/CollectWhileShoot.java @@ -6,13 +6,15 @@ import frc.robot.subsystems.intake.IntakeConstants; import frc.robot.subsystems.shooter.ShooterCommands; import frc.robot.subsystems.shooter.ShooterConstants; +import frc.robot.subsystems.sparkShooter.SparkShooterCommands; +import frc.robot.subsystems.sparkShooter.SparkShooterConstants; import frc.robot.subsystems.transporter.TransporterCommands; import frc.robot.subsystems.transporter.TransporterConstants; public class CollectWhileShoot { public static Command CollectingAndShootingCommand(){ return new ParallelCommandGroup( - ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.SHOOT), + SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.SHOOT), IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.COLLECT_STATE), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); diff --git a/src/main/java/frc/robot/commands/ShootingCommands.java b/src/main/java/frc/robot/commands/ShootingCommands.java index fdde0cd..405ce41 100644 --- a/src/main/java/frc/robot/commands/ShootingCommands.java +++ b/src/main/java/frc/robot/commands/ShootingCommands.java @@ -4,19 +4,21 @@ import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; import frc.robot.subsystems.shooter.ShooterCommands; import frc.robot.subsystems.shooter.ShooterConstants; +import frc.robot.subsystems.sparkShooter.SparkShooterCommands; +import frc.robot.subsystems.sparkShooter.SparkShooterConstants; import frc.robot.subsystems.transporter.TransporterCommands; import frc.robot.subsystems.transporter.TransporterConstants; public class ShootingCommands { public static Command ShootTennisBallCommand() { return new ParallelCommandGroup( - ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.SHOOT), + SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.SHOOT), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); } public static Command EjectTennisBallFromShooter() { return new ParallelCommandGroup( - ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.EJECT), + SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.EJECT), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java index e9c151b..fb1c395 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java @@ -3,6 +3,10 @@ import com.ctre.phoenix.motorcontrol.FollowerType; import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import com.revrobotics.spark.SparkLowLevel; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkMaxConfig; public class ShooterConstants { private static final int @@ -11,7 +15,6 @@ public class ShooterConstants { static final WPI_TalonSRX MASTER_MOTOR = new WPI_TalonSRX(MASTER_MOTOR_ID), FOLLOWER_MOTOR = new WPI_TalonSRX(FOLLOWER_MOTOR_ID); - private static final boolean SHOULD_MASTER_MOTOR_INVERT = true, SHOULD_FOLLOWER_MOTOR_INVERT = false; @@ -41,14 +44,14 @@ private static void configureFollowerMotor() { FOLLOWER_MOTOR.follow(MASTER_MOTOR, FollowerType.PercentOutput); } - public enum ShooterState{ + public enum ShooterState { REST(0), SHOOT(5), EJECT(2); public final double targetVoltage; - ShooterState(double targetVoltage){ + ShooterState(double targetVoltage) { this.targetVoltage = targetVoltage; } } diff --git a/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooter.java b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooter.java new file mode 100644 index 0000000..897da53 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooter.java @@ -0,0 +1,27 @@ +package frc.robot.subsystems.sparkShooter; + + +import com.revrobotics.spark.SparkMax; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class SparkShooter extends SubsystemBase { + private final SparkMax motor = SparkShooterConstants.MOTOR; + + public SparkShooter() { + } + + void stop() { + motor.stopMotor(); + } + + void setTargetState(SparkShooterConstants.SparkShooterState targetState) { + setTargetVoltage(targetState.targetVoltage); + } + + private void setTargetVoltage(double targetVoltage) { + motor.setVoltage(targetVoltage); + } + + +} + diff --git a/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterCommands.java b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterCommands.java new file mode 100644 index 0000000..125fa90 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterCommands.java @@ -0,0 +1,14 @@ +package frc.robot.subsystems.sparkShooter; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.StartEndCommand; +import frc.robot.RobotContainer; + +public class SparkShooterCommands { + public static Command getSetTargetStateCommand(SparkShooterConstants.SparkShooterState targetState) { + return new StartEndCommand( + () -> RobotContainer.SPARK_SHOOTER.setTargetState(targetState), + RobotContainer.SPARK_SHOOTER::stop + ); + } +} diff --git a/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java new file mode 100644 index 0000000..9356bda --- /dev/null +++ b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java @@ -0,0 +1,39 @@ +package frc.robot.subsystems.sparkShooter; + +import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.SparkLowLevel; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.config.SparkBaseConfig; +import com.revrobotics.spark.config.SparkMaxConfig; + +public class SparkShooterConstants { + private static final int MOTOR_ID = 8; + + static final SparkMax MOTOR = new SparkMax(MOTOR_ID, SparkLowLevel.MotorType.kBrushless); + + private static final boolean SHOULD_MOTOR_INVERT = false; + private static final SparkBaseConfig.IdleMode IDLE_MODE = SparkBaseConfig.IdleMode.kBrake; + + private static final double VOLTAGE_LIMIT = 12; + + static { + SparkMaxConfig config = new SparkMaxConfig(); + config.inverted(SHOULD_MOTOR_INVERT); + config.voltageCompensation(VOLTAGE_LIMIT); + config.idleMode(SparkBaseConfig.IdleMode.kBrake); + + MOTOR.configure(config, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kNoPersistParameters); + } + + public enum SparkShooterState { + REST(0), + SHOOT(5), + EJECT(2); + + public final double targetVoltage; + + SparkShooterState(double targetVoltage) { + this.targetVoltage = targetVoltage; + } + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/transporter/Transporter.java b/src/main/java/frc/robot/subsystems/transporter/Transporter.java index 5f61303..f482da3 100644 --- a/src/main/java/frc/robot/subsystems/transporter/Transporter.java +++ b/src/main/java/frc/robot/subsystems/transporter/Transporter.java @@ -4,7 +4,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Transporter extends SubsystemBase { - private final WPI_TalonSRX motor = TransporterConstants.MASTER_MOTOR; + private final WPI_TalonSRX motor = TransporterConstants.MOTOR; public Transporter() { } @@ -18,7 +18,7 @@ void setTargetVoltage(double targetVoltage) { } void stop(){ - TransporterConstants.MASTER_MOTOR.stopMotor(); + TransporterConstants.MOTOR.stopMotor(); TransporterConstants.FOLLOWER_MOTOR.stopMotor(); } } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java b/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java index 0be0566..e46956e 100644 --- a/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java +++ b/src/main/java/frc/robot/subsystems/transporter/TransporterConstants.java @@ -1,55 +1,34 @@ package frc.robot.subsystems.transporter; -import com.ctre.phoenix.motorcontrol.FollowerType; import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; -import edu.wpi.first.units.measure.Voltage; public class TransporterConstants { - private static final int - MASTER_MOTOR_ID = 7, - FOLLOWER_MOTOR_ID = 8; - static final WPI_TalonSRX - MASTER_MOTOR = new WPI_TalonSRX(MASTER_MOTOR_ID), - FOLLOWER_MOTOR = new WPI_TalonSRX(FOLLOWER_MOTOR_ID); - - private static final boolean - SHOULD_MASTER_MOTOR_INVERT = true, - SHOULD_FOLLOWER_MOTOR_INVERT = false; + private static final int MOTOR_ID = 7; + + static final WPI_TalonSRX MOTOR = new WPI_TalonSRX(MOTOR_ID); + + private static final boolean SHOULD_MOTOR_INVERT = true; private static final NeutralMode NEUTRAL_MODE = NeutralMode.Brake; private static final double VOLTAGE_LIMIT = 12; static { - configureMasterMotor(); - configureFollowerMotor(); - } - - private static void configureMasterMotor() { - MASTER_MOTOR.configFactoryDefault(); - MASTER_MOTOR.enableVoltageCompensation(true); - MASTER_MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); - MASTER_MOTOR.setNeutralMode(NEUTRAL_MODE); - MASTER_MOTOR.setInverted(SHOULD_MASTER_MOTOR_INVERT); - } - - private static void configureFollowerMotor() { - FOLLOWER_MOTOR.configFactoryDefault(); - FOLLOWER_MOTOR.enableVoltageCompensation(true); - FOLLOWER_MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); - FOLLOWER_MOTOR.setNeutralMode(NEUTRAL_MODE); - FOLLOWER_MOTOR.setInverted(SHOULD_FOLLOWER_MOTOR_INVERT); - FOLLOWER_MOTOR.follow(MASTER_MOTOR, FollowerType.PercentOutput); + MOTOR.configFactoryDefault(); + MOTOR.enableVoltageCompensation(true); + MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); + MOTOR.setNeutralMode(NEUTRAL_MODE); + MOTOR.setInverted(SHOULD_MOTOR_INVERT); } - public enum TransporterState{ + public enum TransporterState { COLLECT_STATE(3), EJECT_STAGE(-3), REST(0); public final double targetVoltage; - TransporterState(double targetVoltage){ + TransporterState(double targetVoltage) { this.targetVoltage = targetVoltage; } } diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..ac62be8 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,71 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2025.0.3", + "frcYear": "2025", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2025.0.3" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2025.0.3", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.3", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file From 2423a26921b21aef834fd7a3f9302a5b998fd5c8 Mon Sep 17 00:00:00 2001 From: Shm Date: Thu, 25 Dec 2025 21:18:37 -0500 Subject: [PATCH 12/13] reverted shooter to use talon srx --- src/main/java/frc/robot/RobotContainer.java | 15 +++++++-------- .../frc/robot/commands/CollectWhileShoot.java | 2 +- .../java/frc/robot/commands/ShootingCommands.java | 4 ++-- .../subsystems/shooter/ShooterConstants.java | 4 ++-- .../sparkShooter/SparkShooterConstants.java | 2 +- 5 files changed, 13 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 21b314f..2d41b3a 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -13,9 +13,9 @@ import frc.robot.subsystems.intake.Intake; import frc.robot.subsystems.intake.IntakeCommands; import frc.robot.subsystems.intake.IntakeConstants; -import frc.robot.subsystems.sparkShooter.SparkShooter; -import frc.robot.subsystems.sparkShooter.SparkShooterCommands; -import frc.robot.subsystems.sparkShooter.SparkShooterConstants; +import frc.robot.subsystems.shooter.Shooter; +import frc.robot.subsystems.shooter.ShooterCommands; +import frc.robot.subsystems.shooter.ShooterConstants; import frc.robot.subsystems.tank.Tank; import frc.robot.subsystems.transporter.Transporter; import frc.robot.subsystems.transporter.TransporterCommands; @@ -23,8 +23,8 @@ public class RobotContainer { public static final Intake INTAKE = new Intake(); - // public static Shooter SHOOTER = new Shooter(); - public static SparkShooter SPARK_SHOOTER = new SparkShooter(); + public static Shooter SHOOTER = new Shooter(); + // public static SparkShooter SPARK_SHOOTER = new SparkShooter(); public static Transporter TRANSPORTER = new Transporter(); public static final Tank TANK = new Tank(); @@ -40,8 +40,8 @@ private void configureBindings() { private void bindDefaultCommands() { TANK.setDefaultCommand(GeneralCommands.getTankDefaultCommand()); INTAKE.setDefaultCommand(IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.REST)); - // SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); - SPARK_SHOOTER.setDefaultCommand(SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.REST)); + SHOOTER.setDefaultCommand(ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.REST)); +// SPARK_SHOOTER.setDefaultCommand(SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.REST)); TRANSPORTER.setDefaultCommand(TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.REST)); } @@ -49,7 +49,6 @@ private void bindControllerCommands() { OperatorConstants.COLLECT.whileTrue(CollectingCommands.CollectTennisBall()); } - public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); } diff --git a/src/main/java/frc/robot/commands/CollectWhileShoot.java b/src/main/java/frc/robot/commands/CollectWhileShoot.java index 291d210..54bf46b 100644 --- a/src/main/java/frc/robot/commands/CollectWhileShoot.java +++ b/src/main/java/frc/robot/commands/CollectWhileShoot.java @@ -14,7 +14,7 @@ public class CollectWhileShoot { public static Command CollectingAndShootingCommand(){ return new ParallelCommandGroup( - SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.SHOOT), + ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.SHOOT), IntakeCommands.getSetTargetStateCommand(IntakeConstants.IntakeState.COLLECT_STATE), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); diff --git a/src/main/java/frc/robot/commands/ShootingCommands.java b/src/main/java/frc/robot/commands/ShootingCommands.java index 405ce41..96470a9 100644 --- a/src/main/java/frc/robot/commands/ShootingCommands.java +++ b/src/main/java/frc/robot/commands/ShootingCommands.java @@ -12,13 +12,13 @@ public class ShootingCommands { public static Command ShootTennisBallCommand() { return new ParallelCommandGroup( - SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.SHOOT), + ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.SHOOT), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); } public static Command EjectTennisBallFromShooter() { return new ParallelCommandGroup( - SparkShooterCommands.getSetTargetStateCommand(SparkShooterConstants.SparkShooterState.EJECT), + ShooterCommands.getSetTargetStateCommand(ShooterConstants.ShooterState.EJECT), TransporterCommands.getSetTargetStateCommand(TransporterConstants.TransporterState.COLLECT_STATE) ); } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java index fb1c395..0d9ee25 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java @@ -10,8 +10,8 @@ public class ShooterConstants { private static final int - MASTER_MOTOR_ID = 9, - FOLLOWER_MOTOR_ID = 10; + MASTER_MOTOR_ID = 8, + FOLLOWER_MOTOR_ID = 9; static final WPI_TalonSRX MASTER_MOTOR = new WPI_TalonSRX(MASTER_MOTOR_ID), FOLLOWER_MOTOR = new WPI_TalonSRX(FOLLOWER_MOTOR_ID); diff --git a/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java index 9356bda..fc57284 100644 --- a/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java +++ b/src/main/java/frc/robot/subsystems/sparkShooter/SparkShooterConstants.java @@ -7,7 +7,7 @@ import com.revrobotics.spark.config.SparkMaxConfig; public class SparkShooterConstants { - private static final int MOTOR_ID = 8; + private static final int MOTOR_ID = 20; static final SparkMax MOTOR = new SparkMax(MOTOR_ID, SparkLowLevel.MotorType.kBrushless); From 0c03739d428d9275efdd33b3209ec14124121330 Mon Sep 17 00:00:00 2001 From: Shm Date: Thu, 25 Dec 2025 21:22:02 -0500 Subject: [PATCH 13/13] set shooter to use one motor --- .../frc/robot/subsystems/shooter/Shooter.java | 4 +- .../subsystems/shooter/ShooterConstants.java | 41 ++++--------------- 2 files changed, 10 insertions(+), 35 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shooter/Shooter.java b/src/main/java/frc/robot/subsystems/shooter/Shooter.java index 35740d9..8872efd 100644 --- a/src/main/java/frc/robot/subsystems/shooter/Shooter.java +++ b/src/main/java/frc/robot/subsystems/shooter/Shooter.java @@ -4,7 +4,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Shooter extends SubsystemBase { - private final WPI_TalonSRX motor = ShooterConstants.MASTER_MOTOR; + private final WPI_TalonSRX motor = ShooterConstants.MOTOR; public Shooter() { } @@ -18,7 +18,7 @@ void setTargetVoltage(double targetVoltage) { } void stop(){ - ShooterConstants.MASTER_MOTOR.stopMotor(); + ShooterConstants.MOTOR.stopMotor(); ShooterConstants.FOLLOWER_MOTOR.stopMotor(); } } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java index 0d9ee25..2def824 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java @@ -1,47 +1,22 @@ package frc.robot.subsystems.shooter; -import com.ctre.phoenix.motorcontrol.FollowerType; import com.ctre.phoenix.motorcontrol.NeutralMode; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; -import com.revrobotics.spark.SparkLowLevel; -import com.revrobotics.spark.SparkMax; -import com.revrobotics.spark.config.SparkBaseConfig; -import com.revrobotics.spark.config.SparkMaxConfig; public class ShooterConstants { - private static final int - MASTER_MOTOR_ID = 8, - FOLLOWER_MOTOR_ID = 9; - static final WPI_TalonSRX - MASTER_MOTOR = new WPI_TalonSRX(MASTER_MOTOR_ID), - FOLLOWER_MOTOR = new WPI_TalonSRX(FOLLOWER_MOTOR_ID); - private static final boolean - SHOULD_MASTER_MOTOR_INVERT = true, - SHOULD_FOLLOWER_MOTOR_INVERT = false; + private static final int MASTER_MOTOR_ID = 8; + static final WPI_TalonSRX MOTOR = new WPI_TalonSRX(MASTER_MOTOR_ID); + private static final boolean SHOULD_MOTOR_INVERT = true; private static final NeutralMode NEUTRAL_MODE = NeutralMode.Brake; private static final double VOLTAGE_LIMIT = 12; static { - configureMasterMotor(); - configureFollowerMotor(); - } - - private static void configureMasterMotor() { - MASTER_MOTOR.configFactoryDefault(); - MASTER_MOTOR.enableVoltageCompensation(true); - MASTER_MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); - MASTER_MOTOR.setNeutralMode(NEUTRAL_MODE); - MASTER_MOTOR.setInverted(SHOULD_MASTER_MOTOR_INVERT); - } - - private static void configureFollowerMotor() { - FOLLOWER_MOTOR.configFactoryDefault(); - FOLLOWER_MOTOR.enableVoltageCompensation(true); - FOLLOWER_MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); - FOLLOWER_MOTOR.setNeutralMode(NEUTRAL_MODE); - FOLLOWER_MOTOR.setInverted(SHOULD_FOLLOWER_MOTOR_INVERT); - FOLLOWER_MOTOR.follow(MASTER_MOTOR, FollowerType.PercentOutput); + MOTOR.configFactoryDefault(); + MOTOR.enableVoltageCompensation(true); + MOTOR.configVoltageCompSaturation(VOLTAGE_LIMIT); + MOTOR.setNeutralMode(NEUTRAL_MODE); + MOTOR.setInverted(SHOULD_MOTOR_INVERT); } public enum ShooterState {