Skip to content

Commit

Permalink
configuration for CAN of swervedrive
Browse files Browse the repository at this point in the history
  • Loading branch information
24cirinom committed Jan 20, 2024
1 parent 9072792 commit 15e804c
Show file tree
Hide file tree
Showing 4 changed files with 31 additions and 24 deletions.
2 changes: 1 addition & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
21 changes: 11 additions & 10 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
}
7 changes: 2 additions & 5 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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;
Expand Down
25 changes: 17 additions & 8 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 15e804c

Please sign in to comment.