|
4 | 4 | import com.revrobotics.PersistMode; |
5 | 5 | import com.revrobotics.ResetMode; |
6 | 6 | import com.revrobotics.spark.FeedbackSensor; |
7 | | -import com.revrobotics.spark.SparkClosedLoopController; |
8 | | -import com.revrobotics.spark.SparkMax; |
9 | 7 | import com.revrobotics.spark.SparkBase.ControlType; |
| 8 | +import com.revrobotics.spark.SparkClosedLoopController; |
10 | 9 | import com.revrobotics.spark.SparkLowLevel.MotorType; |
11 | | -import com.revrobotics.spark.config.SparkMaxConfig; |
| 10 | +import com.revrobotics.spark.SparkMax; |
12 | 11 | import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; |
13 | | - |
| 12 | +import com.revrobotics.spark.config.SparkMaxConfig; |
14 | 13 | import edu.wpi.first.math.geometry.Rotation2d; |
15 | 14 |
|
16 | 15 | public class IntakeIOSpark implements IntakeIO { |
17 | 16 |
|
18 | | - private SparkMax extenderMotor = new SparkMax(IntakeConstants.INTAKE_EXTENDER_CAN_ID, MotorType.kBrushless); |
19 | | - private SparkMax spinnerMotor = new SparkMax(IntakeConstants.SPINNER_CAN_ID, MotorType.kBrushless); |
| 17 | + private SparkMax extenderMotor = |
| 18 | + new SparkMax(IntakeConstants.canIntakeExtenderMotorId, MotorType.kBrushless); |
| 19 | + private SparkMax spinnerMotor = |
| 20 | + new SparkMax(IntakeConstants.canSpinnerMotorId, MotorType.kBrushless); |
20 | 21 |
|
21 | | - private AbsoluteEncoder extenderEncoder; |
22 | | - SparkClosedLoopController extenderController; |
| 22 | + private AbsoluteEncoder extenderEncoder; |
| 23 | + SparkClosedLoopController extenderController; |
23 | 24 |
|
24 | | - public IntakeIOSpark() |
25 | | - { |
26 | | - SparkMaxConfig extenderConfig = new SparkMaxConfig(); |
| 25 | + public IntakeIOSpark() { |
| 26 | + SparkMaxConfig extenderConfig = new SparkMaxConfig(); |
27 | 27 |
|
28 | | - extenderConfig |
| 28 | + extenderConfig |
29 | 29 | .openLoopRampRate(0.5) |
30 | 30 | .closedLoopRampRate(0.5) |
31 | 31 | .smartCurrentLimit(30) |
32 | 32 | .idleMode(IdleMode.kBrake); |
33 | 33 |
|
34 | | - extenderConfig.closedLoop |
35 | | - .p(IntakeConstants.extenderPID_P) |
36 | | - .i(IntakeConstants.extenderPID_I) |
37 | | - .d(IntakeConstants.extenderPID_D) |
38 | | - .outputRange(IntakeConstants.extenderPID_MINIMUM, |
39 | | - IntakeConstants.extenderPID_MAXIMUM) |
| 34 | + extenderConfig |
| 35 | + .closedLoop |
| 36 | + .p(IntakeConstants.extenderClosedLoopControllerP) |
| 37 | + .i(IntakeConstants.extenderClosedLoopControllerI) |
| 38 | + .d(IntakeConstants.extenderClosedLoopControllerD) |
| 39 | + .outputRange( |
| 40 | + IntakeConstants.extenderClosedLoopControllerMinimumOutput, |
| 41 | + IntakeConstants.extenderClosedLoopControllerMaximumOutput) |
40 | 42 | .feedbackSensor(FeedbackSensor.kAbsoluteEncoder); |
41 | 43 |
|
42 | | - extenderMotor.configure(extenderConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); |
43 | | - |
44 | | - extenderController = extenderMotor.getClosedLoopController(); |
45 | | - extenderEncoder = extenderMotor.getAbsoluteEncoder(); |
46 | | - |
47 | | - |
48 | | - SparkMaxConfig spinnerConfig = new SparkMaxConfig(); |
49 | | - spinnerConfig.inverted(true) |
50 | | - .idleMode(IdleMode.kCoast) |
51 | | - .smartCurrentLimit(30); |
52 | | - |
53 | | - spinnerMotor.configure(spinnerConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); |
54 | | - } |
55 | | - |
56 | | - @Override |
57 | | - public void updateInputs(IntakeIOInputs inputs) |
58 | | - { |
59 | | - inputs.intakeAmperage = extenderMotor.getOutputCurrent(); |
60 | | - inputs.intakeVoltage = extenderMotor.getAppliedOutput() * extenderMotor.getBusVoltage(); |
61 | | - inputs.intakePosition = new Rotation2d(extenderEncoder.getPosition()); |
62 | | - inputs.intakeSpeed = extenderEncoder.getVelocity(); |
63 | | - |
64 | | - inputs.spinnerAmperage = spinnerMotor.getOutputCurrent(); |
65 | | - inputs.spinnerVoltage = spinnerMotor.getAppliedOutput() * spinnerMotor.getBusVoltage(); |
66 | | - inputs.spinnerSpeed = spinnerMotor.getEncoder().getVelocity(); |
67 | | - |
68 | | - inputs.spinnerFaults = spinnerMotor.getFaults(); |
69 | | - inputs.extenderFaults = extenderMotor.getFaults(); |
70 | | - } |
71 | | - |
72 | | - @Override |
73 | | - public void setSpinnerSpeed(double speed) |
74 | | - { |
75 | | - spinnerMotor.set(speed); |
76 | | - } |
77 | | - @Override |
78 | | - public void setIntakePosition(double setpoint) { |
79 | | - extenderController.setSetpoint(setpoint, ControlType.kPosition); |
80 | | - } |
81 | | - |
| 44 | + extenderMotor.configure( |
| 45 | + extenderConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); |
| 46 | + |
| 47 | + extenderController = extenderMotor.getClosedLoopController(); |
| 48 | + extenderEncoder = extenderMotor.getAbsoluteEncoder(); |
| 49 | + |
| 50 | + SparkMaxConfig spinnerConfig = new SparkMaxConfig(); |
| 51 | + spinnerConfig.inverted(true).idleMode(IdleMode.kCoast).smartCurrentLimit(30); |
| 52 | + |
| 53 | + spinnerMotor.configure( |
| 54 | + spinnerConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters); |
| 55 | + } |
| 56 | + |
| 57 | + @Override |
| 58 | + public void updateInputs(IntakeIOInputs inputs) { |
| 59 | + inputs.intakeAmperage = extenderMotor.getOutputCurrent(); |
| 60 | + inputs.intakeVoltage = extenderMotor.getAppliedOutput() * extenderMotor.getBusVoltage(); |
| 61 | + inputs.intakePosition = new Rotation2d(extenderEncoder.getPosition()); |
| 62 | + inputs.intakeSpeed = extenderEncoder.getVelocity(); |
| 63 | + |
| 64 | + inputs.spinnerAmperage = spinnerMotor.getOutputCurrent(); |
| 65 | + inputs.spinnerVoltage = spinnerMotor.getAppliedOutput() * spinnerMotor.getBusVoltage(); |
| 66 | + inputs.spinnerSpeed = spinnerMotor.getEncoder().getVelocity(); |
| 67 | + |
| 68 | + inputs.spinnerFaults = spinnerMotor.getFaults(); |
| 69 | + inputs.extenderFaults = extenderMotor.getFaults(); |
| 70 | + } |
| 71 | + |
| 72 | + @Override |
| 73 | + public void setSpinnerSpeed(double speed) { |
| 74 | + spinnerMotor.set(speed); |
| 75 | + } |
| 76 | + |
| 77 | + @Override |
| 78 | + public void setIntakePosition(double setpoint) { |
| 79 | + extenderController.setSetpoint(setpoint, ControlType.kPosition); |
| 80 | + } |
82 | 81 | } |
0 commit comments