Skip to content

Commit

Permalink
Rename constants file
Browse files Browse the repository at this point in the history
  • Loading branch information
vichik123 committed Jan 16, 2024
1 parent d128b65 commit 9d6970c
Show file tree
Hide file tree
Showing 6 changed files with 33 additions and 33 deletions.
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/swerve/ModuleIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,14 @@ public ModuleIOSim() {
driveMotor =
new TalonFXSim(
1,
1 / SwerveConstants.DRIVE_REDUCTION,
SwerveConstants.DRIVE_MOTOR_MOMENT_OF_INERTIA);
1 / SwerveConstantsNeo.DRIVE_REDUCTION,
SwerveConstantsNeo.DRIVE_MOTOR_MOMENT_OF_INERTIA);

angleMotor =
new TalonFXSim(
1,
1 / SwerveConstants.ANGLE_REDUCTION,
SwerveConstants.ANGLE_MOTOR_MOMENT_OF_INERTIA);
1 / SwerveConstantsNeo.ANGLE_REDUCTION,
SwerveConstantsNeo.ANGLE_MOTOR_MOMENT_OF_INERTIA);

angleController = new PIDController(8, 0, 0, 0.02);
velocityController = new PIDController(3.5, 0, 0.00, 0.02);
Expand All @@ -55,7 +55,7 @@ public void updateInputs(SwerveModuleInputs inputs) {
inputs.driveMotorAppliedVoltage = driveMotor.getAppliedVoltage();
inputs.driveMotorVelocity =
Units.rpsToMetersPerSecond(
driveMotor.getRotorVelocity(), SwerveConstants.WHEEL_DIAMETER / 2);
driveMotor.getRotorVelocity(), SwerveConstantsNeo.WHEEL_DIAMETER / 2);
currentVelocity = inputs.driveMotorVelocity;
inputs.driveMotorVelocitySetpoint = velocitySetpoint;

Expand Down Expand Up @@ -91,7 +91,7 @@ public void setVelocity(double velocity) {

velocitySetpoint = velocity;
driveControl.withVelocity(
Units.metersToRotations(velocity, SwerveConstants.WHEEL_DIAMETER / 2));
Units.metersToRotations(velocity, SwerveConstantsNeo.WHEEL_DIAMETER / 2));
driveMotor.setControl(driveControl);
}

Expand All @@ -104,7 +104,7 @@ public SwerveModuleState getModuleState() {
public SwerveModulePosition getModulePosition() {
return new SwerveModulePosition(
Units.rpsToMetersPerSecond(
driveMotor.getRotorPosition(), SwerveConstants.WHEEL_DIAMETER / 2),
driveMotor.getRotorPosition(), SwerveConstantsNeo.WHEEL_DIAMETER / 2),
currentAngle);
}

Expand Down
22 changes: 11 additions & 11 deletions src/main/java/frc/robot/swerve/ModuleIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ public class ModuleIOSparkMax implements ModuleIO {

private final SimpleMotorFeedforward feedforward =
new SimpleMotorFeedforward(
SwerveConstants.DRIVE_kS, SwerveConstants.DRIVE_kV, SwerveConstants.DRIVE_kA);
SwerveConstantsNeo.DRIVE_kS, SwerveConstantsNeo.DRIVE_kV, SwerveConstantsNeo.DRIVE_kA);

public ModuleIOSparkMax(
int driveMotorID,
Expand All @@ -58,30 +58,30 @@ public ModuleIOSparkMax(
drivePIDController = driveMotor.getPIDController();
driveEncoder = driveMotor.getEncoder();

driveMotor.enableVoltageCompensation(SwerveConstants.VOLT_COMP_SATURATION);
driveMotor.enableVoltageCompensation(SwerveConstantsNeo.VOLT_COMP_SATURATION);
driveMotor.setIdleMode(CANSparkMax.IdleMode.kBrake);
driveMotor.setSmartCurrentLimit(
(int) SwerveConstants.CURRENT_LIMITS_CONFIGS.StatorCurrentLimit);
(int) SwerveConstantsNeo.CURRENT_LIMITS_CONFIGS.StatorCurrentLimit);
driveMotor.setInverted(driveInverted);
driveEncoder.setPositionConversionFactor(SwerveConstants.DRIVE_REDUCTION);
driveEncoder.setVelocityConversionFactor(SwerveConstants.DRIVE_REDUCTION);
driveEncoder.setPositionConversionFactor(SwerveConstantsNeo.DRIVE_REDUCTION);
driveEncoder.setVelocityConversionFactor(SwerveConstantsNeo.DRIVE_REDUCTION);
driveMotor.burnFlash();

angleMotor.restoreFactoryDefaults();
anglePIDController = angleMotor.getPIDController();
angleEncoder = angleMotor.getEncoder();

angleMotor.enableVoltageCompensation(SwerveConstants.VOLT_COMP_SATURATION);
angleMotor.enableVoltageCompensation(SwerveConstantsNeo.VOLT_COMP_SATURATION);
angleMotor.setIdleMode(CANSparkMax.IdleMode.kBrake);
angleMotor.setSmartCurrentLimit(
(int) SwerveConstants.CURRENT_LIMITS_CONFIGS.StatorCurrentLimit);
(int) SwerveConstantsNeo.CURRENT_LIMITS_CONFIGS.StatorCurrentLimit);
angleMotor.setInverted(angleInverted);
anglePIDController.setP(motionMagicConfigs[0]);
anglePIDController.setI(motionMagicConfigs[1]);
anglePIDController.setD(motionMagicConfigs[2]);
anglePIDController.setFF(motionMagicConfigs[3]);
angleEncoder.setPositionConversionFactor(SwerveConstants.ANGLE_REDUCTION);
angleEncoder.setVelocityConversionFactor(SwerveConstants.ANGLE_REDUCTION);
angleEncoder.setPositionConversionFactor(SwerveConstantsNeo.ANGLE_REDUCTION);
angleEncoder.setVelocityConversionFactor(SwerveConstantsNeo.ANGLE_REDUCTION);
angleMotor.burnFlash();
}

Expand Down Expand Up @@ -117,7 +117,7 @@ public void updateInputs(SwerveModuleInputs inputs) {
inputs.angleSetpoint = angleSetpoint;

inputs.moduleDistance =
inputs.driveMotorPosition * SwerveConstants.WHEEL_DIAMETER * Math.PI;
inputs.driveMotorPosition * SwerveConstantsNeo.WHEEL_DIAMETER * Math.PI;
moduleDistance = inputs.moduleDistance;
}

Expand All @@ -137,7 +137,7 @@ public void setAngle(Rotation2d angle) {
@Override
public double getVelocity() {
return Units.rpmToRadsPerSec(driveEncoder.getVelocity())
* (SwerveConstants.WHEEL_DIAMETER / 2);
* (SwerveConstantsNeo.WHEEL_DIAMETER / 2);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import com.ctre.phoenix6.configs.*;
import edu.wpi.first.math.geometry.Translation2d;

public class SwerveConstants {
public class SwerveConstantsNeo {
public static final double[] OFFSETS = {
0.568_219_064_205_476_6,
0.262_061_806_551_545_15,
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@ public class SwerveDrive extends SubsystemBase {
private final LinearFilter accelFilter = LinearFilter.movingAverage(15);
private final SwerveDriveKinematics kinematics =
new SwerveDriveKinematics(
SwerveConstants.WHEEL_POSITIONS[0],
SwerveConstants.WHEEL_POSITIONS[1],
SwerveConstants.WHEEL_POSITIONS[2],
SwerveConstants.WHEEL_POSITIONS[3]);
SwerveConstantsNeo.WHEEL_POSITIONS[0],
SwerveConstantsNeo.WHEEL_POSITIONS[1],
SwerveConstantsNeo.WHEEL_POSITIONS[2],
SwerveConstantsNeo.WHEEL_POSITIONS[3]);
private final SwerveDriveOdometry odometry;
private final Derivative acceleration = new Derivative();
private final SwerveModulePosition[] modulePositions = new SwerveModulePosition[4];
Expand Down Expand Up @@ -246,9 +246,9 @@ public void drive(ChassisSpeeds chassisSpeeds, boolean fieldOriented) {
public void drive(double xOutput, double yOutput, double omegaOutput, boolean fieldOriented) {
ChassisSpeeds chassisSpeeds =
new ChassisSpeeds(
SwerveConstants.MAX_X_Y_VELOCITY * xOutput,
SwerveConstants.MAX_X_Y_VELOCITY * yOutput,
SwerveConstants.MAX_OMEGA_VELOCITY * omegaOutput); // removed angleFF
SwerveConstantsNeo.MAX_X_Y_VELOCITY * xOutput,
SwerveConstantsNeo.MAX_X_Y_VELOCITY * yOutput,
SwerveConstantsNeo.MAX_OMEGA_VELOCITY * omegaOutput); // removed angleFF

drive(chassisSpeeds, fieldOriented);
}
Expand Down Expand Up @@ -300,7 +300,7 @@ public void periodic() {
gyro.updateInputs(loggerInputs);

SwerveDriveKinematics.desaturateWheelSpeeds(
loggerInputs.desiredModuleStates, SwerveConstants.MAX_X_Y_VELOCITY);
loggerInputs.desiredModuleStates, SwerveConstantsNeo.MAX_X_Y_VELOCITY);
for (int i = 0; i < modules.length; i++) {
modules[i].setModuleState(loggerInputs.desiredModuleStates[i]);
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ public void periodic() {
encoderTrigger.update(io.encoderConnected());

if (timer.hasElapsed(1)) {
io.updateOffset(SwerveConstants.OFFSETS[number - 1]);
io.updateOffset(SwerveConstantsNeo.OFFSETS[number - 1]);
timer.reset();
}
}
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/swerve/commands/XboxDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.swerve.SwerveConstants;
import frc.robot.swerve.SwerveConstantsNeo;
import frc.robot.swerve.SwerveDrive;

public class XboxDrive extends Command {
Expand All @@ -19,11 +19,11 @@ public XboxDrive(SwerveDrive swerveDrive, XboxController xboxController) {
@Override
public void execute() {
swerveDrive.drive(
MathUtil.applyDeadband(-xboxController.getLeftY(), SwerveConstants.XBOX_DEADBAND),
MathUtil.applyDeadband(-xboxController.getLeftX(), SwerveConstants.XBOX_DEADBAND),
MathUtil.applyDeadband(-xboxController.getLeftY(), SwerveConstantsNeo.XBOX_DEADBAND),
MathUtil.applyDeadband(-xboxController.getLeftX(), SwerveConstantsNeo.XBOX_DEADBAND),
MathUtil.applyDeadband(
-xboxController.getRightX() * SwerveConstants.STEERING_MULTIPLIER,
SwerveConstants.XBOX_DEADBAND),
-xboxController.getRightX() * SwerveConstantsNeo.STEERING_MULTIPLIER,
SwerveConstantsNeo.XBOX_DEADBAND),
true);
}
}

0 comments on commit 9d6970c

Please sign in to comment.