|
1 | | -public class IntakeIOSparkMax { |
2 | | - |
| 1 | +package frc.robot.subsystems.intake; |
| 2 | + |
| 3 | +import static frc.robot.Constants.NEO_CURRENT_LIMIT; |
| 4 | + |
| 5 | +import com.revrobotics.RelativeEncoder; |
| 6 | +import com.revrobotics.spark.SparkBase; |
| 7 | +import com.revrobotics.spark.SparkBase.PersistMode; |
| 8 | +import com.revrobotics.spark.SparkBase.ResetMode; |
| 9 | +import com.revrobotics.spark.SparkFlex; |
| 10 | +import com.revrobotics.spark.SparkLowLevel; |
| 11 | +import com.revrobotics.spark.SparkLowLevel.MotorType; |
| 12 | +import com.revrobotics.spark.config.SparkBaseConfig; |
| 13 | +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; |
| 14 | +import com.revrobotics.spark.config.SparkFlexConfig; |
| 15 | + |
| 16 | +import edu.wpi.first.math.controller.ProfiledPIDController; |
| 17 | +import edu.wpi.first.math.trajectory.TrapezoidProfile; |
| 18 | +import edu.wpi.first.wpilibj.DigitalInput; |
| 19 | +import org.littletonrobotics.junction.Logger; |
| 20 | + |
| 21 | +public class IntakeIOSparkMax implements IntakeIO{ |
| 22 | + private SparkFlex frontMotor; |
| 23 | + private SparkFlex backMotor; |
| 24 | + private RelativeEncoder encoder; |
| 25 | + |
| 26 | + private ProfiledPIDController pidController = new ProfiledPIDController(0, 0, 0, new TrapezoidProfile.Constraints(MAX_VELOCITY,MAX_ACCERLERATION)); |
| 27 | + |
| 28 | + public IntakeIOSparkMax() { |
| 29 | + frontMotor = new SparkFlex(IntakeConstants.FRONT_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); |
| 30 | + backMotor = new SparkFlex(IntakeConstants.BACK_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); |
| 31 | + |
| 32 | + encoder = frontMotor.getEncoder(); |
| 33 | + |
| 34 | + SparkFlexConfig frontConfig = new SparkFlexConfig(); |
| 35 | + |
| 36 | + frontConfig |
| 37 | + .idleMode(SparkBaseConfig.IdleMode.kBrake) |
| 38 | + .voltageCompensation(12) |
| 39 | + .smartCurrentLimit(NEO_CURRENT_LIMIT); |
| 40 | + |
| 41 | + SparkFlexConfig backConfig = new SparkFlexConfig(); |
| 42 | + |
| 43 | + backConfig.apply(frontConfig); |
| 44 | + backConfig.follow(frontMotor); |
| 45 | + |
| 46 | + frontMotor.configure(frontConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); |
| 47 | + backMotor.configure(backConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters); |
| 48 | + } |
| 49 | + |
| 50 | + @Override |
| 51 | + public void updateInputs(IntakeIOInputs inputs) { |
| 52 | + inputs.velocityRPM = getRPM(); |
| 53 | + inputs.appliedVoltage = frontMotor.getAppliedOutput() * frontMotor.getBusVoltage(); |
| 54 | + inputs.motorCurrent =frontMotor.getOutputCurrent(); |
| 55 | + } |
| 56 | + |
| 57 | + @Override |
| 58 | + public double getRPM() { |
| 59 | + return encoder.getVelocity(); |
| 60 | + } |
| 61 | + |
| 62 | + @Override |
| 63 | + public void setPIDGains(double Kp, double Ki, double Kd) { |
| 64 | + pidController.setPID(Kp, Ki, Kd); |
| 65 | + } |
| 66 | + |
| 67 | + @Override |
| 68 | + public void setVoltage(double voltage) { |
| 69 | + frontMotor.setVoltage(voltage); |
| 70 | + Logger.recordOutput("Shooter/Set Voltage", voltage); |
| 71 | + } |
| 72 | + |
| 73 | + @Override |
| 74 | + public double getVoltage() { |
| 75 | + return frontMotor.getAppliedOutput() * frontMotor.getBusVoltage(); |
| 76 | + } |
| 77 | + |
| 78 | + @Override |
| 79 | + public void setRPM(double rpm) { |
| 80 | + double voltage = pidController.calculate(getRPM(), rpm); |
| 81 | + frontMotor.setVoltage(voltage); |
| 82 | + } |
| 83 | + @Override |
| 84 | + public void setDirection(boolean forward){ |
| 85 | + frontMotor.setInverted(forward); |
| 86 | + } |
3 | 87 | } |
| 88 | + |
0 commit comments