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] 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