From 9250abdfafc4de767b23c6ec4de8719c8712b5ad Mon Sep 17 00:00:00 2001 From: mayalian Date: Sat, 21 Feb 2026 17:05:07 -0800 Subject: [PATCH] index code done --- ThriftTsConfig | 2 +- .../robot/command/testing/IndexCommand.java | 4 +-- .../frc/robot/constant/IndexConstants.java | 4 +++ .../frc/robot/subsystem/IndexSubsystem.java | 25 +++++++++++++------ src/proto | 2 +- 5 files changed, 25 insertions(+), 12 deletions(-) diff --git a/ThriftTsConfig b/ThriftTsConfig index fec6408..f065183 160000 --- a/ThriftTsConfig +++ b/ThriftTsConfig @@ -1 +1 @@ -Subproject commit fec6408130cc5ac485b5cb0da47113894c493cc5 +Subproject commit f065183998d5be203e7f4500280d54c1bfec0d93 diff --git a/src/main/java/frc/robot/command/testing/IndexCommand.java b/src/main/java/frc/robot/command/testing/IndexCommand.java index fce79a6..4384782 100644 --- a/src/main/java/frc/robot/command/testing/IndexCommand.java +++ b/src/main/java/frc/robot/command/testing/IndexCommand.java @@ -15,12 +15,12 @@ public IndexCommand(IndexSubsystem baseSubsystem, double speed) { @Override public void execute() { - m_indexSubsystem.runMotor(m_speed); + m_indexSubsystem.runMotors(m_speed); } @Override public void end(boolean interrupted) { - m_indexSubsystem.stopMotor(); + m_indexSubsystem.stopMotors(); } @Override diff --git a/src/main/java/frc/robot/constant/IndexConstants.java b/src/main/java/frc/robot/constant/IndexConstants.java index 4e16c5c..82a2801 100644 --- a/src/main/java/frc/robot/constant/IndexConstants.java +++ b/src/main/java/frc/robot/constant/IndexConstants.java @@ -3,4 +3,8 @@ public class IndexConstants { public static final int indexMotorID = 36; public static final double indexMotorSpeed = 0.45; + public static final boolean indexMotorInverted = false; + public static final int feedMotorID = 0; + public static final double feedMotorSpeed = 0; + public static final boolean feedMotorInverted = false; } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystem/IndexSubsystem.java b/src/main/java/frc/robot/subsystem/IndexSubsystem.java index 0a92435..4ad60b8 100644 --- a/src/main/java/frc/robot/subsystem/IndexSubsystem.java +++ b/src/main/java/frc/robot/subsystem/IndexSubsystem.java @@ -15,6 +15,7 @@ public class IndexSubsystem extends SubsystemBase { private static IndexSubsystem instance; private final SparkFlex m_indexMotor; + private final SparkFlex m_feedMotor; public static IndexSubsystem GetInstance() { if (instance == null) { @@ -25,22 +26,30 @@ public static IndexSubsystem GetInstance() { private IndexSubsystem() { m_indexMotor = new SparkFlex(IndexConstants.indexMotorID, MotorType.kBrushless); - configureMotor(); + m_feedMotor = new SparkFlex(IndexConstants.feedMotorID, MotorType.kBrushless); + configureMotors(); } - private void configureMotor() { - SparkFlexConfig config = new SparkFlexConfig(); - config.idleMode(IdleMode.kBrake); - config.inverted(true); + private void configureMotors() { + SparkFlexConfig indexConfig = new SparkFlexConfig(); + indexConfig.idleMode(IdleMode.kBrake); + indexConfig.inverted(IndexConstants.indexMotorInverted); - m_indexMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); + SparkFlexConfig feedConfig = new SparkFlexConfig(); + feedConfig.idleMode(IdleMode.kBrake); + feedConfig.inverted(IndexConstants.feedMotorInverted); + + m_indexMotor.configure(indexConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); + m_feedMotor.configure(feedConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); } - public void runMotor(double speed) { + public void runMotors(double speed) { m_indexMotor.set(MathUtil.clamp(speed, -1.0, 1.0)); + m_feedMotor.set(MathUtil.clamp(speed, -1.0, 1.0)); } - public void stopMotor() { + public void stopMotors() { m_indexMotor.set(0.0); + m_feedMotor.set(0.0); } } diff --git a/src/proto b/src/proto index 4720743..5031e30 160000 --- a/src/proto +++ b/src/proto @@ -1 +1 @@ -Subproject commit 47207432b8869a80b6369c1a8233b50935096fb9 +Subproject commit 5031e309a16437337efec7fb8ed2453f704a4fff