Skip to content

Commit 6bf417b

Browse files
committed
SparkFlex
1 parent 468422f commit 6bf417b

File tree

1 file changed

+7
-48
lines changed

1 file changed

+7
-48
lines changed

src/main/java/frc/robot/SwerveModule.java

Lines changed: 7 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -8,64 +8,43 @@
88

99
import com.ctre.phoenix6.hardware.CANcoder;
1010
import com.revrobotics.RelativeEncoder;
11-
import com.revrobotics.sim.SparkMaxSim;
1211
import com.revrobotics.spark.SparkBase.PersistMode;
1312
import com.revrobotics.spark.SparkBase.ResetMode;
14-
import com.revrobotics.spark.SparkMax;
13+
import com.revrobotics.spark.SparkFlex;
1514
import com.revrobotics.spark.SparkLowLevel.MotorType;
1615
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
17-
import com.revrobotics.spark.config.SparkMaxConfig;
16+
import com.revrobotics.spark.config.SparkFlexConfig;
1817

1918
import edu.wpi.first.math.controller.PIDController;
2019
import edu.wpi.first.math.geometry.Rotation2d;
2120
import edu.wpi.first.math.kinematics.SwerveModulePosition;
2221
import edu.wpi.first.math.kinematics.SwerveModuleState;
23-
import edu.wpi.first.math.system.plant.DCMotor;
24-
import edu.wpi.first.math.system.plant.LinearSystemId;
25-
import edu.wpi.first.wpilibj.RobotBase;
26-
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
2722

2823
/**
2924
* Contains all the hardware and controllers for a swerve module.
3025
*/
3126
public class SwerveModule {
3227
private final PIDController m_steerController = new PIDController(kP, kI, kD);
3328
private final CANcoder m_CANCoder;
34-
private final SparkMax m_driveMotor;
35-
private final SparkMax m_steerMotor;
36-
37-
private final SparkMaxSim m_steerMotorSim;
38-
private final DCMotorSim m_driveMotorModel;
39-
private final DCMotorSim m_steerMotorModel;
29+
private final SparkFlex m_driveMotor;
30+
private final SparkFlex m_steerMotor;
4031

4132
private final RelativeEncoder m_relativeEncoder;
4233

4334
public SwerveModule(int canId, int drivePort, int steerPort) {
4435
m_CANCoder = new CANcoder(canId);
45-
m_driveMotor = new SparkMax(drivePort, MotorType.kBrushless);
46-
m_steerMotor = new SparkMax(steerPort, MotorType.kBrushless);
47-
m_steerMotorSim = new SparkMaxSim(m_steerMotor, DCMotor.getNEO(1));
36+
m_driveMotor = new SparkFlex(drivePort, MotorType.kBrushless);
37+
m_steerMotor = new SparkFlex(steerPort, MotorType.kBrushless);
4838
m_relativeEncoder = m_driveMotor.getEncoder();
4939

50-
var config = new SparkMaxConfig();
40+
var config = new SparkFlexConfig();
5141
config.idleMode(IdleMode.kBrake).voltageCompensation(12);
5242
config.openLoopRampRate(kRampRate).closedLoopRampRate(kRampRate);
5343
// Helps with encoder precision (not set in stone)
5444
config.encoder.uvwAverageDepth(kEncoderDepth).uvwMeasurementPeriod(kEncoderMeasurementPeriod);
5545
config.smartCurrentLimit(kSteerSmartCurrentLimit).secondaryCurrentLimit(kSteerPeakCurrentLimit);
5646
m_steerMotor.configure(config, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
5747
m_steerController.enableContinuousInput(0, 360);
58-
if (RobotBase.isSimulation()) {
59-
m_driveMotorModel = new DCMotorSim(
60-
LinearSystemId.createDCMotorSystem(kV / (2 * Math.PI), kA / (2 * Math.PI)),
61-
DCMotor.getKrakenX60(1).withReduction(kGearRatio));
62-
m_steerMotorModel = new DCMotorSim(
63-
LinearSystemId.createDCMotorSystem(kV / (2 * Math.PI), 0.0001 / (2 * Math.PI)),
64-
DCMotor.getKrakenX60(1));
65-
} else {
66-
m_driveMotorModel = null;
67-
m_steerMotorModel = null;
68-
}
6948

7049
}
7150

@@ -148,25 +127,5 @@ public void setModuleState(SwerveModuleState state) {
148127
m_driveMotor.setVoltage(state.speedMetersPerSecond);
149128
double turnPower = m_steerController.calculate(getModuleAngle(), state.angle.getDegrees());
150129
m_steerMotor.setVoltage(turnPower);
151-
updateSim();
152-
}
153-
154-
private void updateSim() {
155-
if (RobotBase.isSimulation()) {
156-
// var driveMotorState = m_driveMotor.getSimState();
157-
// m_driveMotorModel.setInputVoltage(driveMotorState.getMotorVoltage());
158-
m_driveMotorModel.update(0.02);
159-
// driveMotorState.setRotorVelocity(m_driveMotorModel.getAngularVelocityRPM() /
160-
// 60);
161-
// driveMotorState.setRawRotorPosition(m_driveMotorModel.getAngularPositionRotations());
162-
var encoderSimState = m_CANCoder.getSimState();
163-
// These used to be CAN IDs, but apparently any other value causes complete
164-
// destabilization of the swerve sim. Do not touch.
165-
m_steerMotorSim.iterate(30, 32, 0.02);
166-
m_steerMotorModel.setInputVoltage(m_steerMotorSim.getAppliedOutput() * 12);
167-
m_steerMotorModel.update(0.02);
168-
encoderSimState.setRawPosition(m_steerMotorModel.getAngularPositionRotations());
169-
encoderSimState.setVelocity(m_steerMotorModel.getAngularVelocityRPM());
170-
}
171130
}
172131
}

0 commit comments

Comments
 (0)