From fc0023d67a77ff93dc8a573a6bd96a66b9cda64e Mon Sep 17 00:00:00 2001 From: Programming-3 <2491nomythic@gmail.com> Date: Tue, 12 Mar 2024 17:56:31 -0500 Subject: [PATCH 01/10] Enabled logging --- src/main/java/frc/robot/RobotContainer.java | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1d43c7ea..42b4971d 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -60,6 +60,7 @@ import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.PS4Controller; import edu.wpi.first.wpilibj.PowerDistribution; @@ -137,7 +138,10 @@ public RobotContainer() { Preferences.initBoolean("Use Limelight", true); Preferences.initBoolean("Use 2 Limelights", true); Preferences.initDouble("wait # of seconds", 0); - + + DataLogManager.start(); //Start logging + DriverStation.startDataLog(DataLogManager.getLog()); //Joystick Data logging + // DataLogManager.start(); // URCL.start(); // SignalLogger.setPath("/media/sda1/ctre-logs/"); From 64b0a0394f784c6f6db2cd5e5400385946ff908b Mon Sep 17 00:00:00 2001 From: Programming-3 <2491nomythic@gmail.com> Date: Tue, 12 Mar 2024 19:03:55 -0500 Subject: [PATCH 02/10] Enabled intake logging --- .../frc/robot/subsystems/IntakeSubsystem.java | 25 +++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java index 7351a00a..3351b5ed 100644 --- a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -10,6 +10,9 @@ import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; +import edu.wpi.first.util.datalog.DataLog; +import edu.wpi.first.util.datalog.DoubleLogEntry; +import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -20,6 +23,13 @@ public class IntakeSubsystem extends SubsystemBase { CANSparkMax intake2; SparkAnalogSensor m_DistanceSensor; + + DoubleLogEntry percentOutputLog1; + DoubleLogEntry percentOutputLog2; + + DoubleLogEntry currentLog1; + DoubleLogEntry currentLog2; + double intakeRunSpeed; public IntakeSubsystem() { intake1 = new CANSparkMax(IntakeConstants.INTAKE_1_MOTOR, MotorType.kBrushless); @@ -40,6 +50,16 @@ public IntakeSubsystem() { intake2.setSmartCurrentLimit(25, 40, 1000); intake1.burnFlash(); intake2.burnFlash(); + + DataLog log = DataLogManager.getLog(); + percentOutputLog1 = new DoubleLogEntry(log, "/intake/motor1/output"); + percentOutputLog2 = new DoubleLogEntry(log, "/intake/motor2/output"); + + currentLog1 = new DoubleLogEntry(log, "/intake/motor1/current"); + currentLog2 = new DoubleLogEntry(log, "/intake/motor2/current"); + + + } public void intakeYes(double intakeRunSpeed) { @@ -58,5 +78,10 @@ public boolean isNoteIn() { public void periodic() { SmartDashboard.putNumber("voltage sensor output", m_DistanceSensor.getVoltage()); SmartDashboard.putBoolean("is note in", isNoteIn()); + + currentLog1.append(intake1.getOutputCurrent()); + currentLog2.append(intake2.getOutputCurrent()); + percentOutputLog1.append(intake1.getAppliedOutput()); + percentOutputLog2.append(intake2.getAppliedOutput()); } } From 2853d55a9481ae941d51d6ea0cc16f162638f4c1 Mon Sep 17 00:00:00 2001 From: Liam Sykes <78829557+trixydevs@users.noreply.github.com> Date: Thu, 14 Mar 2024 17:56:59 -0500 Subject: [PATCH 03/10] Add a helper class for logging motor data. --- .../java/frc/robot/helpers/MotorLogger.java | 34 +++++++++++++++++++ 1 file changed, 34 insertions(+) create mode 100644 src/main/java/frc/robot/helpers/MotorLogger.java diff --git a/src/main/java/frc/robot/helpers/MotorLogger.java b/src/main/java/frc/robot/helpers/MotorLogger.java new file mode 100644 index 00000000..02b20870 --- /dev/null +++ b/src/main/java/frc/robot/helpers/MotorLogger.java @@ -0,0 +1,34 @@ +package frc.robot.helpers; + +import com.ctre.phoenix6.hardware.TalonFX; +import com.revrobotics.CANSparkMax; + +import edu.wpi.first.util.datalog.DataLog; +import edu.wpi.first.util.datalog.DoubleLogEntry; + +/** + * logs moter data to a logger + */ +public class MotorLogger { + DoubleLogEntry percentOutput; + DoubleLogEntry current; + DoubleLogEntry velocity; + + public MotorLogger(DataLog log, String path) { + percentOutput = new DoubleLogEntry(log, path + "/output"); + current = new DoubleLogEntry(log, path + "/current"); + velocity = new DoubleLogEntry(log, path + "/velocity"); + } + + public void log(CANSparkMax motor) { + current.append(motor.getOutputCurrent()); + percentOutput.append(motor.getAppliedOutput()); + velocity.append(motor.getEncoder().getVelocity()/60); + } + + public void log(TalonFX motor) { + current.append(motor.getStatorCurrent().getValueAsDouble()); + percentOutput.append(motor.get()); + velocity.append(motor.getVelocity().getValueAsDouble()); + } +} From 18a7b07687b904c62edfe9f49538b0fb60065bac Mon Sep 17 00:00:00 2001 From: Liam Sykes <78829557+trixydevs@users.noreply.github.com> Date: Thu, 14 Mar 2024 17:57:33 -0500 Subject: [PATCH 04/10] Swich intake logging to use helper class. --- .../frc/robot/subsystems/IntakeSubsystem.java | 28 ++++++------------- 1 file changed, 8 insertions(+), 20 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java index 3351b5ed..aa909dc9 100644 --- a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -11,24 +11,20 @@ import com.revrobotics.CANSparkLowLevel.MotorType; import edu.wpi.first.util.datalog.DataLog; -import edu.wpi.first.util.datalog.DoubleLogEntry; import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; - import frc.robot.settings.Constants.IntakeConstants; +import frc.robot.helpers.MotorLogger; +import frc.robot.settings.Constants.IntakeConstants; public class IntakeSubsystem extends SubsystemBase { /** Creates a new Intake. */ CANSparkMax intake1; CANSparkMax intake2; SparkAnalogSensor m_DistanceSensor; - - DoubleLogEntry percentOutputLog1; - DoubleLogEntry percentOutputLog2; - - DoubleLogEntry currentLog1; - DoubleLogEntry currentLog2; + MotorLogger motorLogger1; + MotorLogger motorLogger2; double intakeRunSpeed; public IntakeSubsystem() { @@ -52,14 +48,8 @@ public IntakeSubsystem() { intake2.burnFlash(); DataLog log = DataLogManager.getLog(); - percentOutputLog1 = new DoubleLogEntry(log, "/intake/motor1/output"); - percentOutputLog2 = new DoubleLogEntry(log, "/intake/motor2/output"); - - currentLog1 = new DoubleLogEntry(log, "/intake/motor1/current"); - currentLog2 = new DoubleLogEntry(log, "/intake/motor2/current"); - - - + motorLogger1 = new MotorLogger(log, "/intake/motor1"); + motorLogger2 = new MotorLogger(log, "/intake/motor2"); } public void intakeYes(double intakeRunSpeed) { @@ -79,9 +69,7 @@ public void periodic() { SmartDashboard.putNumber("voltage sensor output", m_DistanceSensor.getVoltage()); SmartDashboard.putBoolean("is note in", isNoteIn()); - currentLog1.append(intake1.getOutputCurrent()); - currentLog2.append(intake2.getOutputCurrent()); - percentOutputLog1.append(intake1.getAppliedOutput()); - percentOutputLog2.append(intake2.getAppliedOutput()); + motorLogger1.log(intake1); + motorLogger2.log(intake2); } } From 249fd28ec43b3c4bbe13ec53a27d260a0cdf8a6f Mon Sep 17 00:00:00 2001 From: Liam Sykes <78829557+trixydevs@users.noreply.github.com> Date: Thu, 14 Mar 2024 18:59:18 -0500 Subject: [PATCH 05/10] add logging to shooter and indexer --- .../java/frc/robot/subsystems/IndexerSubsystem.java | 8 +++++++- .../java/frc/robot/subsystems/ShooterSubsystem.java | 12 ++++++++++++ 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java index 537efd39..fe2bc675 100644 --- a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java @@ -4,8 +4,11 @@ import com.ctre.phoenix6.configs.TalonFXConfigurator; import com.ctre.phoenix6.hardware.TalonFX; import com.revrobotics.SparkAnalogSensor; + +import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.helpers.MotorLogger; import frc.robot.settings.Constants.IndexerConstants; public class IndexerSubsystem extends SubsystemBase { @@ -13,6 +16,7 @@ public class IndexerSubsystem extends SubsystemBase { SparkAnalogSensor m_DistanceSensor; CurrentLimitsConfigs currentLimitsConfigs; TalonFXConfigurator configurator; + MotorLogger motorLogger; public IndexerSubsystem() { m_IndexerMotor = new TalonFX(IndexerConstants.INDEXER_MOTOR); @@ -23,6 +27,8 @@ public IndexerSubsystem() { currentLimitsConfigs.SupplyCurrentLimitEnable = true; configurator = m_IndexerMotor.getConfigurator(); configurator.apply(currentLimitsConfigs); + + motorLogger = new MotorLogger(DataLogManager.getLog(), "/indexer/motor"); } public void on() { @@ -41,6 +47,6 @@ public void set(double speed) { } @Override public void periodic() { - SmartDashboard.putNumber("indexer current", m_IndexerMotor.getSupplyCurrent().getValueAsDouble()); + motorLogger.log(m_IndexerMotor); } } diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index fe23162d..3b381d8a 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -17,8 +17,11 @@ import com.revrobotics.RelativeEncoder; import frc.robot.commands.AngleShooter; import frc.robot.commands.RotateRobot; +import frc.robot.helpers.MotorLogger; import frc.robot.settings.Constants; import frc.robot.settings.Constants.ShooterConstants; +import edu.wpi.first.util.datalog.DataLog; +import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -46,6 +49,9 @@ public class ShooterSubsystem extends SubsystemBase { AngleShooter angleShooter; int accumulativeTurns; int runsValid; + + MotorLogger motorLoggerR; + MotorLogger motorLoggerL; /** Creates a new Shooter. */ public ShooterSubsystem(double runSpeed) { @@ -78,6 +84,10 @@ public ShooterSubsystem(double runSpeed) { configuratorR.apply(PIDRightconfigs); configuratorL.apply(PIDLeftconfigs); + + DataLog log = DataLogManager.getLog(); + motorLoggerL = new MotorLogger(log, "/shooter/motorL"); + motorLoggerR = new MotorLogger(log, "/shooter/motorR"); } private void adjCurrentLimit( double supplyLimit, double statorLimit){ currentLimitConfigs.SupplyCurrentLimit = supplyLimit; @@ -133,6 +143,8 @@ public void periodic() { } else { runsValid = 0; } + motorLoggerL.log(shooterL); + motorLoggerR.log(shooterR); } } From cca57ef5381b849e7eadb4acc5c1b8b1a29b97ed Mon Sep 17 00:00:00 2001 From: Liam Sykes <78829557+trixydevs@users.noreply.github.com> Date: Thu, 14 Mar 2024 19:07:47 -0500 Subject: [PATCH 06/10] logging more intake data --- src/main/java/frc/robot/subsystems/IntakeSubsystem.java | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java index aa909dc9..2ff7bddb 100644 --- a/src/main/java/frc/robot/subsystems/IntakeSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakeSubsystem.java @@ -10,7 +10,9 @@ import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; +import edu.wpi.first.util.datalog.BooleanLogEntry; import edu.wpi.first.util.datalog.DataLog; +import edu.wpi.first.util.datalog.DoubleLogEntry; import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.Preferences; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -25,6 +27,8 @@ public class IntakeSubsystem extends SubsystemBase { MotorLogger motorLogger1; MotorLogger motorLogger2; + DoubleLogEntry logDistance; + BooleanLogEntry logNoteIn; double intakeRunSpeed; public IntakeSubsystem() { @@ -50,6 +54,8 @@ public IntakeSubsystem() { DataLog log = DataLogManager.getLog(); motorLogger1 = new MotorLogger(log, "/intake/motor1"); motorLogger2 = new MotorLogger(log, "/intake/motor2"); + logDistance = new DoubleLogEntry(log, "/intake/noteDistance"); + logNoteIn = new BooleanLogEntry(log, "/intake/noteIn"); } public void intakeYes(double intakeRunSpeed) { @@ -71,5 +77,7 @@ public void periodic() { motorLogger1.log(intake1); motorLogger2.log(intake2); + logDistance.append(m_DistanceSensor.getVoltage()); + logNoteIn.append(isNoteIn()); } } From 552a5847e71d67bd6fe5ea8c8dc2e51dfc9b749b Mon Sep 17 00:00:00 2001 From: Liam Sykes <78829557+trixydevs@users.noreply.github.com> Date: Thu, 14 Mar 2024 19:40:10 -0500 Subject: [PATCH 07/10] note tracking added to indexer --- src/main/java/frc/robot/RobotContainer.java | 4 +-- .../robot/subsystems/IndexerSubsystem.java | 29 +++++++++++++++++-- 2 files changed, 29 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 42b4971d..a3689817 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -173,7 +173,7 @@ public RobotContainer() { driveTrainInst(); - if(intakeExists) {intakeInst();} + if(intakeExists) {intakeInst(); /* Must happen before indexInit */} if(shooterExists) {shooterInst();} if(angleShooterExists) {angleShooterInst();} if(climberExists) {climberInst();} @@ -226,7 +226,7 @@ private void climberInst() { climber = new Climber(); } private void indexInit() { - indexer = new IndexerSubsystem(); + indexer = new IndexerSubsystem(intakeExists ? intake::isNoteIn : () -> false); } private void indexCommandInst() { defaulNoteHandlingCommand = new IndexCommand(indexer, ShootIfReadySup, AimWhileMovingSup, shooter, intake, driveTrain, angleShooterSubsystem, HumanPlaySup, StageAngleSup, SubwooferAngleSup, GroundIntakeSup, FarStageAngleSup, OperatorPreRevSup, intakeReverse); diff --git a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java index fe2bc675..97188d13 100644 --- a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java @@ -1,10 +1,13 @@ package frc.robot.subsystems; +import java.util.function.BooleanSupplier; + import com.ctre.phoenix6.configs.CurrentLimitsConfigs; import com.ctre.phoenix6.configs.TalonFXConfigurator; import com.ctre.phoenix6.hardware.TalonFX; import com.revrobotics.SparkAnalogSensor; +import edu.wpi.first.util.datalog.DoubleLogEntry; import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -13,14 +16,18 @@ public class IndexerSubsystem extends SubsystemBase { TalonFX m_IndexerMotor; - SparkAnalogSensor m_DistanceSensor; CurrentLimitsConfigs currentLimitsConfigs; TalonFXConfigurator configurator; + BooleanSupplier isNoteIn; + double noteStart; + boolean wasNoteIn = false; MotorLogger motorLogger; + DoubleLogEntry notePositionLog; - public IndexerSubsystem() { + public IndexerSubsystem(BooleanSupplier isNoteIn) { m_IndexerMotor = new TalonFX(IndexerConstants.INDEXER_MOTOR); m_IndexerMotor.setInverted(false); + this.isNoteIn = isNoteIn; currentLimitsConfigs = new CurrentLimitsConfigs(); currentLimitsConfigs.SupplyCurrentLimit = IndexerConstants.CURRENT_LIMIT; @@ -29,6 +36,7 @@ public IndexerSubsystem() { configurator.apply(currentLimitsConfigs); motorLogger = new MotorLogger(DataLogManager.getLog(), "/indexer/motor"); + notePositionLog = new DoubleLogEntry(DataLogManager.getLog(),"/indexer/notePosistion"); } public void on() { @@ -45,8 +53,25 @@ public void reverse() { public void set(double speed) { m_IndexerMotor.set(speed); } + + public void trackNote() { + boolean noteIn = isNoteIn.getAsBoolean(); + if (!wasNoteIn && noteIn) { + noteStart = m_IndexerMotor.getPosition().getValueAsDouble(); + } + wasNoteIn = noteIn; + } + + public double getNotePosition() { + return m_IndexerMotor.getPosition().getValueAsDouble() - noteStart; + } + @Override public void periodic() { + trackNote(); motorLogger.log(m_IndexerMotor); + double pos = getNotePosition(); + notePositionLog.append(pos); + SmartDashboard.putNumber("note pos", pos); } } From 3647105bb696120029791e97d9905c7c3bc9435c Mon Sep 17 00:00:00 2001 From: zack0022 <146891713+zack0022@users.noreply.github.com> Date: Sat, 16 Mar 2024 20:41:08 -0500 Subject: [PATCH 08/10] changed method name --- src/main/java/frc/robot/RobotContainer.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 196c9425..e7d91785 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -239,7 +239,7 @@ private void climberInst() { climber = new Climber(); } private void indexInit() { - indexer = new IndexerSubsystem(intakeExists ? intake::isNoteIn : () -> false); + indexer = new IndexerSubsystem(intakeExists ? intake::isNoteSeen : () -> false); } private void indexCommandInst() { defaulNoteHandlingCommand = new IndexCommand(indexer, ShootIfReadySup, AimWhileMovingSup, shooter, intake, driveTrain, angleShooterSubsystem, HumanPlaySup, StageAngleSup, SubwooferAngleSup, GroundIntakeSup, FarStageAngleSup, OperatorPreRevSup, intakeReverse); @@ -540,4 +540,4 @@ public void disabledInit() { new InstantCommand(angleShooterSubsystem::stop, angleShooterSubsystem); } } -} \ No newline at end of file +} From 3b982b254718424522ad85a2f9d32742324ca276 Mon Sep 17 00:00:00 2001 From: zack0022 <146891713+zack0022@users.noreply.github.com> Date: Sat, 16 Mar 2024 20:42:32 -0500 Subject: [PATCH 09/10] rename motor --- .../frc/robot/subsystems/IndexerSubsystem.java | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java index 34d5eba4..662c7aba 100644 --- a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java @@ -58,7 +58,7 @@ public IndexerSubsystem(BooleanSupplier isNoteIn) { .withMotionMagicCruiseVelocity(IndexerConstants.INDEXER_CRUISE_VELOCITY) .withMotionMagicAcceleration(IndexerConstants.INDEXER_ACCELERATION) .withMotionMagicJerk(IndexerConstants.INDEXER_JERK)); - indexerMotor.getConfigurator().apply(talonFXConfig); + m_IndexerMotor.getConfigurator().apply(talonFXConfig); } /** @@ -67,13 +67,13 @@ public IndexerSubsystem(BooleanSupplier isNoteIn) { * uses percentage of full power */ public void on() { - indexerMotor.set(IndexerConstants.INDEXER_INTAKE_SPEED); + m_IndexerMotor.set(IndexerConstants.INDEXER_INTAKE_SPEED); } /** sets the indxer motor's percent-of-full-power to 0 */ public void off() { - indexerMotor.set(0); + m_IndexerMotor.set(0); } /** * sets the indexer motor to -INDEXER_INTAKE_SPEED (from constants) @@ -81,14 +81,14 @@ public void off() { * uses percentage of full power */ public void reverse() { - indexerMotor.set(-IndexerConstants.INDEXER_INTAKE_SPEED); + m_IndexerMotor.set(-IndexerConstants.INDEXER_INTAKE_SPEED); } /** * sets the percentage-of-full-power on the indexer * @param speed the desired speed, from -1 to 1 */ public void set(double speed) { - indexerMotor.set(speed); + m_IndexerMotor.set(speed); } /** * uses the indexer motor's onboard Motion Magic control to move the indexer forward. To move backwards, use negative inches. @@ -96,9 +96,9 @@ public void set(double speed) { */ public void forwardInches(double inches) { double rotationsRequested = inches/IndexerConstants.MOTOR_ROTATIONS_TO_INCHES; - double position = indexerMotor.getPosition().getValueAsDouble()+rotationsRequested; + double position = m_IndexerMotor.getPosition().getValueAsDouble()+rotationsRequested; MotionMagicVoltage distanceRequest = new MotionMagicVoltage(position); - indexerMotor.setControl(distanceRequest); + m_IndexerMotor.setControl(distanceRequest); } public void trackNote() { @@ -118,7 +118,7 @@ public double getNotePosition() { */ public void magicRPS(double RPS) { MotionMagicVelocityVoltage speedRequest = new MotionMagicVelocityVoltage(RPS); - indexerMotor.setControl(speedRequest); + m_IndexerMotor.setControl(speedRequest); } @Override From 8b22a36e501331ba5088d6bb5431e404c954b2e5 Mon Sep 17 00:00:00 2001 From: zack0022 <146891713+zack0022@users.noreply.github.com> Date: Sat, 16 Mar 2024 20:43:36 -0500 Subject: [PATCH 10/10] added needed import --- src/main/java/frc/robot/subsystems/IndexerSubsystem.java | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java index 662c7aba..451d32f0 100644 --- a/src/main/java/frc/robot/subsystems/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IndexerSubsystem.java @@ -7,6 +7,7 @@ import com.ctre.phoenix6.configs.MotorOutputConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.configs.TalonFXConfigurator; import com.ctre.phoenix6.controls.MotionMagicDutyCycle; import com.ctre.phoenix6.controls.MotionMagicVelocityDutyCycle; import com.ctre.phoenix6.controls.MotionMagicVelocityVoltage;