From 15e804c567030910c901b1ba542ee682078a2dd1 Mon Sep 17 00:00:00 2001 From: 24cirinom <112493487+24cirinom@users.noreply.github.com> Date: Sat, 20 Jan 2024 13:25:35 -0600 Subject: [PATCH] configuration for CAN of swervedrive --- .vscode/settings.json | 2 +- src/main/java/frc/robot/Constants.java | 21 ++++++++-------- src/main/java/frc/robot/Robot.java | 7 ++---- .../subsystems/drive/ModuleIOSparkMax.java | 25 +++++++++++++------ 4 files changed, 31 insertions(+), 24 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 8f86a00..ea54bb5 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -36,7 +36,7 @@ "editor.defaultFormatter": "richardwillis.vscode-spotless-gradle" }, "[java]": { - "editor.defaultFormatter": "richardwillis.vscode-spotless-gradle" + "editor.defaultFormatter": "ms-vsliveshare.vsliveshare" }, "java.debug.settings.onBuildFailureProceed": true } diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index eb5152a..8367577 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -34,16 +34,17 @@ public static enum Mode { /** Replaying from a log file. */ REPLAY } + public static final class DriveConstants { - // SPARK MAX CAN IDs - public static final int kFrontLeftDrivingCanId = 10; - public static final int kRearLeftDrivingCanId = 8; - public static final int kFrontRightDrivingCanId = 2; - public static final int kRearRightDrivingCanId = 4; - - public static final int kFrontLeftTurningCanId = 11; - public static final int kRearLeftTurningCanId = 9; - public static final int kFrontRightTurningCanId = 3; - public static final int kRearRightTurningCanId = 5; + // SPARK MAX CAN IDs + public static final int kFrontLeftDrivingCanId = 10; + public static final int kRearLeftDrivingCanId = 8; + public static final int kFrontRightDrivingCanId = 2; + public static final int kRearRightDrivingCanId = 4; + + public static final int kFrontLeftTurningCanId = 11; + public static final int kRearLeftTurningCanId = 9; + public static final int kFrontRightTurningCanId = 3; + public static final int kRearRightTurningCanId = 5; } } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 29429d6..00efa03 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -1,7 +1,5 @@ -//Awtybots 5829 2024 Codebase -//Thank you FRC 6328 and FRC 3015! - - +// Awtybots 5829 2024 Codebase +// Thank you FRC 6328 and FRC 3015! // Copyright 2021-2024 FRC 6328 // http://github.com/Mechanical-Advantage @@ -16,7 +14,6 @@ // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. - package frc.robot; import edu.wpi.first.wpilibj2.command.Command; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java index 6c79134..de2b42e 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java @@ -22,6 +22,7 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.RobotController; +import frc.robot.Constants.DriveConstants; import java.util.Queue; /** @@ -55,27 +56,35 @@ public class ModuleIOSparkMax implements ModuleIO { public ModuleIOSparkMax(int index) { switch (index) { + // Front left case 0: - driveSparkMax = new CANSparkMax(1, MotorType.kBrushless); - turnSparkMax = new CANSparkMax(2, MotorType.kBrushless); + driveSparkMax = + new CANSparkMax(DriveConstants.kFrontLeftDrivingCanId, MotorType.kBrushless); + turnSparkMax = new CANSparkMax(DriveConstants.kFrontLeftTurningCanId, MotorType.kBrushless); turnAbsoluteEncoder = new AnalogInput(0); absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED break; + // Front right case 1: - driveSparkMax = new CANSparkMax(3, MotorType.kBrushless); - turnSparkMax = new CANSparkMax(4, MotorType.kBrushless); + driveSparkMax = + new CANSparkMax(DriveConstants.kFrontRightDrivingCanId, MotorType.kBrushless); + turnSparkMax = + new CANSparkMax(DriveConstants.kFrontRightTurningCanId, MotorType.kBrushless); turnAbsoluteEncoder = new AnalogInput(1); absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED break; + // Rear left case 2: - driveSparkMax = new CANSparkMax(5, MotorType.kBrushless); - turnSparkMax = new CANSparkMax(6, MotorType.kBrushless); + driveSparkMax = new CANSparkMax(DriveConstants.kRearLeftDrivingCanId, MotorType.kBrushless); + turnSparkMax = new CANSparkMax(DriveConstants.kRearLeftTurningCanId, MotorType.kBrushless); turnAbsoluteEncoder = new AnalogInput(2); absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED break; + // Rear right case 3: - driveSparkMax = new CANSparkMax(7, MotorType.kBrushless); - turnSparkMax = new CANSparkMax(8, MotorType.kBrushless); + driveSparkMax = + new CANSparkMax(DriveConstants.kRearRightDrivingCanId, MotorType.kBrushless); + turnSparkMax = new CANSparkMax(DriveConstants.kRearRightTurningCanId, MotorType.kBrushless); turnAbsoluteEncoder = new AnalogInput(3); absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED break;