Skip to content

Commit

Permalink
renamed the method that applies the inversion on on the indexer motor…
Browse files Browse the repository at this point in the history
…, UNTESTED (could make the indexer move the wrong way)
  • Loading branch information
2491NoMythic committed Nov 24, 2024
1 parent ae29fd2 commit de6b70d
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/subsystems/IndexerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.revrobotics.SparkAnalogSensor;

import edu.wpi.first.util.datalog.DoubleLogEntry;
import edu.wpi.first.wpilibj.DataLogManager;
Expand All @@ -38,7 +37,6 @@ public class IndexerSubsystem extends SubsystemBase {

public IndexerSubsystem(BooleanSupplier isNoteIn) {
m_IndexerMotor = new TalonFX(IndexerConstants.INDEXER_MOTOR);
m_IndexerMotor.setInverted(false);
m_IndexerMotor.setNeutralMode(NeutralModeValue.Brake);
this.isNoteIn = isNoteIn;

Expand All @@ -47,8 +45,10 @@ public IndexerSubsystem(BooleanSupplier isNoteIn) {
currentLimitsConfigs.SupplyCurrentLimitEnable = true;

configurator = m_IndexerMotor.getConfigurator();
configurator.apply(new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive));
configurator.apply(currentLimitsConfigs);


motorLogger = new MotorLogger(DataLogManager.getLog(), "/indexer/motor");
notePositionLog = new DoubleLogEntry(DataLogManager.getLog(),"/indexer/notePosistion");

Expand All @@ -63,8 +63,7 @@ public IndexerSubsystem(BooleanSupplier isNoteIn) {
.withMotionMagicCruiseVelocity(IndexerConstants.INDEXER_CRUISE_VELOCITY)
.withMotionMagicAcceleration(IndexerConstants.INDEXER_ACCELERATION)
.withMotionMagicJerk(IndexerConstants.INDEXER_JERK));
m_IndexerMotor.getConfigurator().apply(talonFXConfig);

configurator.apply(talonFXConfig);
}
/**
* sets the speed of the indexer motor to INDEXER_INTAKE_SPEED (from constants)
Expand Down

0 comments on commit de6b70d

Please sign in to comment.