From eedd0bed6a85414a2dc7385aeb5835e5be88f8b2 Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Wed, 18 Feb 2026 21:24:30 -0500 Subject: [PATCH 1/8] Made tunnable pid numbers work + made shooter idle mode coast --- src/main/java/frc/robot/subsystems/ShooterSubsystem.java | 5 +++-- .../robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 09d8d678..56850a14 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -9,6 +9,7 @@ import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.config.SparkBaseConfig; import com.revrobotics.spark.config.SparkMaxConfig; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.constants.Constants; @@ -36,7 +37,7 @@ public ShooterSubsystem(SparkMaxPidMotorIo io) { io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); followerConfig = new SparkMaxConfig(); - followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true); + followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true).idleMode(IdleMode.kCoast); followerMotor.configure(followerConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); } @@ -74,7 +75,7 @@ public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) { } public static SparkMaxPidMotor createMotor() { - return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, true); + return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, false); } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java index 5435c8e2..950e1233 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java @@ -51,7 +51,7 @@ public SparkMaxPidMotor(int id, SparkMaxPidConfig pidConfig) { config .smartCurrentLimit(pidConfig.getCurrentLimit()) .closedLoopRampRate(RAMP_RATE) - .idleMode(IdleMode.kBrake); + .idleMode(IdleMode.kCoast); config .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) @@ -92,7 +92,7 @@ public void configurePID(SparkMaxPidConfig params) { .closedLoop .pid(params.getP(), params.getI(), params.getD()) .iZone(params.getIZone()) - .feedForward.kV(pidConfig.getFF()); + .feedForward.kV(params.getFF()); if (params.getUsesMaxMotion()) { config .closedLoop From 1cafcb812262ea26b8b5e78789a9c1dd43b6bcf7 Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Thu, 19 Feb 2026 18:19:24 -0500 Subject: [PATCH 2/8] chnaged brake mode --- .../frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java index 950e1233..c9c9c523 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java @@ -51,7 +51,7 @@ public SparkMaxPidMotor(int id, SparkMaxPidConfig pidConfig) { config .smartCurrentLimit(pidConfig.getCurrentLimit()) .closedLoopRampRate(RAMP_RATE) - .idleMode(IdleMode.kCoast); + .idleMode(IdleMode.kBrake); config .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) From be66dedcc2032833d5cf6446dcb2a809dcb8faf5 Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Thu, 19 Feb 2026 18:51:38 -0500 Subject: [PATCH 3/8] added idle mode --- src/main/java/frc/robot/subsystems/ShooterSubsystem.java | 1 + .../logging/io/pidmotor/MockSparkMaxPidMotorIo.java | 5 +++++ .../logging/io/pidmotor/RealSparkMaxPidMotorIo.java | 9 +++++++++ .../utils/logging/io/pidmotor/SparkMaxPidMotor.java | 8 +++++++- .../utils/logging/io/pidmotor/SparkMaxPidMotorIo.java | 4 ++++ 5 files changed, 26 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 56850a14..e32d315f 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -35,6 +35,7 @@ public class ShooterSubsystem extends SubsystemBase { public ShooterSubsystem(SparkMaxPidMotorIo io) { this.io = io; io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning + io.idleMode(IdleMode.kCoast); followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); followerConfig = new SparkMaxConfig(); followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true).idleMode(IdleMode.kCoast); diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java index aed7bbd2..9911e03f 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java @@ -4,6 +4,8 @@ package frc.robot.utils.logging.io.pidmotor; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; + import frc.robot.utils.logging.input.MotorLoggableInputs; import frc.robot.utils.logging.io.motor.MockSparkMaxIo; @@ -38,4 +40,7 @@ public void setPid(double pidP, double pidI, double pidD, double iZone, double p @Override public void resetEncoderPosition(double positionRotations) { } + @Override + public void idleMode(IdleMode mode){ + } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java index 78122684..e563933d 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java @@ -1,6 +1,11 @@ package frc.robot.utils.logging.io.pidmotor; +import com.revrobotics.PersistMode; +import com.revrobotics.ResetMode; import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.config.SparkMaxConfig; + import frc.robot.utils.logging.input.MotorLoggableInputs; import frc.robot.utils.logging.io.motor.RealSparkMaxIo; @@ -45,4 +50,8 @@ public void setPid(double pidP, double pidI, double pidD, double iZone, double p public void resetEncoderPosition(double positionRotations) { pidMotor.getEncoder().setPosition(positionRotations); } + @Override + public void idleMode(IdleMode mode){ + pidMotor.idleMode(mode); + } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java index c9c9c523..72085426 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java @@ -9,6 +9,8 @@ import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import com.revrobotics.spark.config.SparkMaxConfig; +import frc.robot.constants.Constants; + /** * A Wrapper utility to encapsulate the NEO motor with PID capability. This is simply a wrapper with * some convenient defaults and initializations that make programming the PID of the NEO easier. @@ -78,7 +80,11 @@ public SparkMaxPidMotor(int id, SparkMaxPidConfig pidConfig) { neoMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); } - + public void idleMode(IdleMode mode){ + SparkMaxConfig config = new SparkMaxConfig(); + config.idleMode(mode); + neoMotor.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); + } /** * Reconfigure the PID fully using some of the values from motor params. * This method uses the PID, iZone, FF, maxVelocity, maxAcceleration and allowedError to reconfigure diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java index 630e7f10..fbc3ee04 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java @@ -1,6 +1,8 @@ package frc.robot.utils.logging.io.pidmotor; import com.revrobotics.spark.SparkBase; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; + import frc.robot.utils.logging.io.motor.SparkMaxIo; /** @@ -56,4 +58,6 @@ public interface SparkMaxPidMotorIo extends SparkMaxIo { * @param pidFF the FF value to set */ void setPid(double pidP, double pidI, double pidD, double iZone, double pidFF); + + void idleMode(IdleMode mode); } From d65fdb6161ce2da8ae17420a60992e3fe40ea55c Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Thu, 19 Feb 2026 21:46:39 -0500 Subject: [PATCH 4/8] commit --- src/main/java/frc/robot/subsystems/ShooterSubsystem.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index e32d315f..8288bc2f 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -34,8 +34,8 @@ public class ShooterSubsystem extends SubsystemBase { public ShooterSubsystem(SparkMaxPidMotorIo io) { this.io = io; - io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning io.idleMode(IdleMode.kCoast); + io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); followerConfig = new SparkMaxConfig(); followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true).idleMode(IdleMode.kCoast); From fb8a816f9d3b2f1424677e8c8977dc9304857a9e Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Fri, 20 Feb 2026 19:05:33 -0500 Subject: [PATCH 5/8] Made chnages ohad wanted --- .../java/frc/robot/subsystems/ShooterSubsystem.java | 5 +++-- .../logging/io/pidmotor/MockSparkMaxPidMotorIo.java | 3 --- .../logging/io/pidmotor/RealSparkMaxPidMotorIo.java | 4 ---- .../logging/io/pidmotor/SparkMaxPidConfig.java | 13 +++++++++++++ .../utils/logging/io/pidmotor/SparkMaxPidMotor.java | 7 +------ .../logging/io/pidmotor/SparkMaxPidMotorIo.java | 1 - 6 files changed, 17 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 8288bc2f..39e35ef9 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -34,7 +34,6 @@ public class ShooterSubsystem extends SubsystemBase { public ShooterSubsystem(SparkMaxPidMotorIo io) { this.io = io; - io.idleMode(IdleMode.kCoast); io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); followerConfig = new SparkMaxConfig(); @@ -76,7 +75,9 @@ public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) { } public static SparkMaxPidMotor createMotor() { - return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, false); + SparkMaxPidConfig config = new SparkMaxPidConfig(false); + config.setIdleMode(IdleMode.kCoast); + return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, config); } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java index 9911e03f..52be4e43 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java @@ -40,7 +40,4 @@ public void setPid(double pidP, double pidI, double pidD, double iZone, double p @Override public void resetEncoderPosition(double positionRotations) { } - @Override - public void idleMode(IdleMode mode){ - } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java index e563933d..928a1293 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java @@ -50,8 +50,4 @@ public void setPid(double pidP, double pidI, double pidD, double iZone, double p public void resetEncoderPosition(double positionRotations) { pidMotor.getEncoder().setPosition(positionRotations); } - @Override - public void idleMode(IdleMode mode){ - pidMotor.idleMode(mode); - } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java index 03ad4a50..8b1c462c 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java @@ -1,5 +1,7 @@ package frc.robot.utils.logging.io.pidmotor; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; + /** * Value container helper class for configuring a PidMotor. */ @@ -12,6 +14,7 @@ public class SparkMaxPidConfig { public static final double MAX_VELOCITY = 5000; public static final double MAX_ACCELERATION = 10000; public static final double ALLOWED_ERROR = 1.0; + public static final IdleMode DEFAULT_MODE = IdleMode.kBrake; private double p = DEFAULT_P; private double i = DEFAULT_I; @@ -19,6 +22,7 @@ public class SparkMaxPidConfig { private double iZone = DEFAULT_IZONE; private double ff = DEFAULT_FF; private int currentLimit = 20; + private IdleMode mode = DEFAULT_MODE; /** * This is the cruise velocity for the MAX_MOTION config. */ @@ -130,4 +134,13 @@ public double getAllowedError() { public boolean getUsesMaxMotion() { return usesMaxMotion; } + + public void setIdleMode(IdleMode mode){ + this.mode = mode; + } + + public IdleMode getIdleMode(){ + return mode; + } } + diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java index 72085426..ccad39c8 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotor.java @@ -53,7 +53,7 @@ public SparkMaxPidMotor(int id, SparkMaxPidConfig pidConfig) { config .smartCurrentLimit(pidConfig.getCurrentLimit()) .closedLoopRampRate(RAMP_RATE) - .idleMode(IdleMode.kBrake); + .idleMode(pidConfig.getIdleMode()); config .closedLoop .feedbackSensor(FeedbackSensor.kPrimaryEncoder) @@ -80,11 +80,6 @@ public SparkMaxPidMotor(int id, SparkMaxPidConfig pidConfig) { neoMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); } - public void idleMode(IdleMode mode){ - SparkMaxConfig config = new SparkMaxConfig(); - config.idleMode(mode); - neoMotor.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); - } /** * Reconfigure the PID fully using some of the values from motor params. * This method uses the PID, iZone, FF, maxVelocity, maxAcceleration and allowedError to reconfigure diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java index fbc3ee04..7d51336a 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java @@ -59,5 +59,4 @@ public interface SparkMaxPidMotorIo extends SparkMaxIo { */ void setPid(double pidP, double pidI, double pidD, double iZone, double pidFF); - void idleMode(IdleMode mode); } From f5d2007b790cd57e5cbfe95c293ef45f03c2e33a Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Fri, 20 Feb 2026 19:39:59 -0500 Subject: [PATCH 6/8] Tested and added tunable numbers for shooter --- src/main/java/frc/robot/RobotContainer.java | 2 +- .../frc/robot/commands/shooter/SpinShooter.java | 1 + .../frc/robot/subsystems/ShooterSubsystem.java | 17 ++++++++++++----- .../logging/io/pidmotor/SparkMaxPidConfig.java | 5 +++-- 4 files changed, 17 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 7b9ac010..91813020 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -348,7 +348,7 @@ public void putShuffleboardCommands() { new SpinFeeder(feederSubsystem)); SmartDashboard.putData( - "Spin Shooter", + "Spins Shooter", new SpinShooter(shooterSubsystem, Constants.SHOOTER_SPEED)); SmartDashboard.putData( diff --git a/src/main/java/frc/robot/commands/shooter/SpinShooter.java b/src/main/java/frc/robot/commands/shooter/SpinShooter.java index e21102ce..ee5d165d 100644 --- a/src/main/java/frc/robot/commands/shooter/SpinShooter.java +++ b/src/main/java/frc/robot/commands/shooter/SpinShooter.java @@ -25,6 +25,7 @@ public void initialize() { @Override public void execute() { + System.out.println("CALIFONIA"); subsystem.setPidVelocity(speed); } diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 39e35ef9..8390a9af 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -21,6 +21,7 @@ import frc.robot.utils.logging.io.pidmotor.SparkMaxPidConfig; import frc.robot.utils.logging.io.pidmotor.SparkMaxPidMotor; import frc.robot.utils.logging.io.pidmotor.SparkMaxPidMotorIo; +import frc.robot.utils.motor.TunablePIDManager; import frc.robot.utils.simulation.MotorSimulator; import frc.robot.utils.simulation.RobotVisualizer; @@ -31,16 +32,23 @@ public class ShooterSubsystem extends SubsystemBase { private final SparkMaxPidMotorIo io; private final SparkMax followerMotor; private final SparkMaxConfig followerConfig; - + private final TunablePIDManager pidManager; public ShooterSubsystem(SparkMaxPidMotorIo io) { + this.pidManager = new TunablePIDManager(LOGGING_NAME, io, createPidConfig()); this.io = io; - io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning + // io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); followerConfig = new SparkMaxConfig(); followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true).idleMode(IdleMode.kCoast); followerMotor.configure(followerConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); } + private static SparkMaxPidConfig createPidConfig() { + return new SparkMaxPidConfig(false) + .setCurrentLimit(Constants.NEO_CURRENT_LIMIT) + .setAllowedError(.1) + .setIdleMode(IdleMode.kCoast); + } // setSpeed expects a power value from -1 to 1 public void setSpeed(double speed) { @@ -58,6 +66,7 @@ public void setPidVelocity(double velocity) { @Override public void periodic() { + pidManager.periodic(); io.periodic(); } @@ -75,9 +84,7 @@ public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) { } public static SparkMaxPidMotor createMotor() { - SparkMaxPidConfig config = new SparkMaxPidConfig(false); - config.setIdleMode(IdleMode.kCoast); - return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, config); + return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, createPidConfig()); } } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java index 8b1c462c..472adb2c 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java @@ -6,7 +6,7 @@ * Value container helper class for configuring a PidMotor. */ public class SparkMaxPidConfig { - public static final double DEFAULT_P = 0.01; + public static final double DEFAULT_P = 0.0; public static final double DEFAULT_I = 0; public static final double DEFAULT_D = 0.0; public static final double DEFAULT_IZONE = 0.0; @@ -135,8 +135,9 @@ public boolean getUsesMaxMotion() { return usesMaxMotion; } - public void setIdleMode(IdleMode mode){ + public SparkMaxPidConfig setIdleMode(IdleMode mode){ this.mode = mode; + return this; } public IdleMode getIdleMode(){ From 81fbcae846305f59049e7e8adee57c2dd7763b78 Mon Sep 17 00:00:00 2001 From: Jackson Date: Fri, 20 Feb 2026 20:02:17 -0500 Subject: [PATCH 7/8] Update src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java Co-authored-by: Ohad <34323545+armadilloz@users.noreply.github.com> --- .../frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java index 472adb2c..1f84e607 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java @@ -14,7 +14,7 @@ public class SparkMaxPidConfig { public static final double MAX_VELOCITY = 5000; public static final double MAX_ACCELERATION = 10000; public static final double ALLOWED_ERROR = 1.0; - public static final IdleMode DEFAULT_MODE = IdleMode.kBrake; + public static final IdleMode DEFAULT_IDLE_MODE = IdleMode.kBrake; private double p = DEFAULT_P; private double i = DEFAULT_I; From 1195a7225b9c5a0b725100b74eef0678898256a8 Mon Sep 17 00:00:00 2001 From: Jackson Wess Date: Fri, 20 Feb 2026 20:02:57 -0500 Subject: [PATCH 8/8] Fixxed reviewed changes --- src/main/java/frc/robot/commands/shooter/SpinShooter.java | 1 - .../robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java | 1 - .../robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java | 1 - .../frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java | 2 +- .../frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java | 1 - 5 files changed, 1 insertion(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/commands/shooter/SpinShooter.java b/src/main/java/frc/robot/commands/shooter/SpinShooter.java index ee5d165d..e21102ce 100644 --- a/src/main/java/frc/robot/commands/shooter/SpinShooter.java +++ b/src/main/java/frc/robot/commands/shooter/SpinShooter.java @@ -25,7 +25,6 @@ public void initialize() { @Override public void execute() { - System.out.println("CALIFONIA"); subsystem.setPidVelocity(speed); } diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java index 52be4e43..d42c3afe 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/MockSparkMaxPidMotorIo.java @@ -4,7 +4,6 @@ package frc.robot.utils.logging.io.pidmotor; -import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import frc.robot.utils.logging.input.MotorLoggableInputs; import frc.robot.utils.logging.io.motor.MockSparkMaxIo; diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java index 928a1293..a14820b3 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/RealSparkMaxPidMotorIo.java @@ -1,6 +1,5 @@ package frc.robot.utils.logging.io.pidmotor; -import com.revrobotics.PersistMode; import com.revrobotics.ResetMode; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java index 472adb2c..7f21c718 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidConfig.java @@ -6,7 +6,7 @@ * Value container helper class for configuring a PidMotor. */ public class SparkMaxPidConfig { - public static final double DEFAULT_P = 0.0; + public static final double DEFAULT_P = 0.01; public static final double DEFAULT_I = 0; public static final double DEFAULT_D = 0.0; public static final double DEFAULT_IZONE = 0.0; diff --git a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java index 7d51336a..c33237f2 100644 --- a/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java +++ b/src/main/java/frc/robot/utils/logging/io/pidmotor/SparkMaxPidMotorIo.java @@ -1,7 +1,6 @@ package frc.robot.utils.logging.io.pidmotor; import com.revrobotics.spark.SparkBase; -import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import frc.robot.utils.logging.io.motor.SparkMaxIo;