From 11512e140c0cd7a9f8a730e36df30ce8b44c7aa3 Mon Sep 17 00:00:00 2001 From: Team 2648 Date: Thu, 27 Mar 2025 19:04:10 -0400 Subject: [PATCH] added the indexer --- src/main/java/frc/robot/RobotContainer.java | 10 ++++++ .../frc/robot/constants/IndexerConstants.java | 15 +++++++++ .../java/frc/robot/subsystems/Indexer.java | 32 +++++++++++++++++++ 3 files changed, 57 insertions(+) create mode 100644 src/main/java/frc/robot/constants/IndexerConstants.java create mode 100644 src/main/java/frc/robot/subsystems/Indexer.java diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1aff18c..b6872aa 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -14,6 +14,7 @@ import frc.robot.subsystems.ClimberPivot; import frc.robot.subsystems.ClimberRollers; import frc.robot.subsystems.Drivetrain; import frc.robot.subsystems.Elevator; +import frc.robot.subsystems.Indexer; import frc.robot.subsystems.Manipulator; import java.util.function.IntSupplier; @@ -42,6 +43,8 @@ public class RobotContainer { private Elevator elevator; //private ElevatorSysID elevator; + private Indexer indexer; + private Manipulator manipulator; private ManipulatorPivot manipulatorPivot; @@ -63,6 +66,8 @@ public class RobotContainer { elevator = new Elevator(); //elevator = new ElevatorSysID(); + indexer = new Indexer(); + manipulator = new Manipulator(); manipulatorPivot = new ManipulatorPivot(); @@ -117,6 +122,10 @@ public class RobotContainer { elevator.setDefaultCommand( elevator.maintainPosition() ); + + indexer.setDefaultCommand( + indexer.runIndexer(() -> 0) + ); manipulatorPivot.setDefaultCommand( @@ -140,6 +149,7 @@ public class RobotContainer { driver.leftTrigger().whileTrue( manipulator.runUntilCollected(() -> 0.75) + .alongWith(indexer.runIndexer(() -> .75)) .until(() -> manipulator.getCoralBeamBreak() == false) .andThen(manipulator.retractCommand(() -> .1)) ); diff --git a/src/main/java/frc/robot/constants/IndexerConstants.java b/src/main/java/frc/robot/constants/IndexerConstants.java new file mode 100644 index 0000000..f33aa4d --- /dev/null +++ b/src/main/java/frc/robot/constants/IndexerConstants.java @@ -0,0 +1,15 @@ +package frc.robot.constants; + +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.config.SparkMaxConfig; + +public class IndexerConstants { + public static final int kIndexerMotorID = 16; + + public static final SparkMaxConfig motorConfig = new SparkMaxConfig(); + + static{ + motorConfig.smartCurrentLimit(40) + .idleMode(IdleMode.kCoast); + }; +} diff --git a/src/main/java/frc/robot/subsystems/Indexer.java b/src/main/java/frc/robot/subsystems/Indexer.java new file mode 100644 index 0000000..806d694 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Indexer.java @@ -0,0 +1,32 @@ +package frc.robot.subsystems; + +import java.util.function.DoubleSupplier; + +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkBase.PersistMode; +import com.revrobotics.spark.SparkBase.ResetMode; +import com.revrobotics.spark.SparkLowLevel.MotorType; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.constants.IndexerConstants; + +public class Indexer extends SubsystemBase { + private SparkMax indexerMotor; + + public Indexer() { + indexerMotor = new SparkMax(IndexerConstants.kIndexerMotorID, MotorType.kBrushless); + + indexerMotor.configure( + IndexerConstants.motorConfig, + ResetMode.kResetSafeParameters, + PersistMode.kPersistParameters + ); + } + + public Command runIndexer(DoubleSupplier speed) { + return run(() -> { + indexerMotor.set(speed.getAsDouble()); + }); + } +}