Skip to content

Commit

Permalink
feat: add config ternaries for multiple robots
Browse files Browse the repository at this point in the history
  • Loading branch information
rutmanz committed Jan 17, 2024
1 parent a4d0e0c commit a6ef3da
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 8 deletions.
14 changes: 12 additions & 2 deletions src/main/java/org/team1540/robot2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,11 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final Mode currentMode = Robot.isReal() ? Mode.REAL : Mode.SIM;
public static final boolean IS_COMPETITION_ROBOT = true;
private static final Mode simMode = Mode.SIM; // Can also be Mode.REPLAY


public static final Mode currentMode = Robot.isReal() ? Mode.REAL : simMode;

public enum Mode {
/**
Expand All @@ -32,8 +36,14 @@ public enum Mode {

public static final double LOOP_PERIOD_SECS = 0.02;

public static class SwerveConfig {
public static final String CAN_BUS = IS_COMPETITION_ROBOT ? "" : "";
public static final int FRONT_LEFT = IS_COMPETITION_ROBOT ? 3 : 0;
public static final int FRONT_RIGHT = IS_COMPETITION_ROBOT ? 4 : 0;
public static final int BACK_LEFT = IS_COMPETITION_ROBOT ? 7 : 0;
public static final int BACK_RIGHT = IS_COMPETITION_ROBOT ? 1 : 0;
}
public static class Drivetrain {
public static final String CAN_BUS = "";
public static final double DRIVE_GEAR_RATIO = (50.0 / 14.0) * (17.0 / 27.0) * (45.0 / 15.0);
public static final double TURN_GEAR_RATIO = 150.0 / 7.0;
public static final boolean IS_TURN_MOTOR_INVERTED = true;
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/org/team1540/robot2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

import org.team1540.robot2024.Constants.SwerveConfig;
import org.team1540.robot2024.commands.FeedForwardCharacterization;
import org.team1540.robot2024.commands.SwerveDriveCommand;
import org.team1540.robot2024.subsystems.drive.*;
Expand Down Expand Up @@ -42,10 +44,10 @@ public RobotContainer() {
drivetrain =
new Drivetrain(
new GyroIONavx(),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(3, SwerveFactory.SwerveCorner.FRONT_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(4, SwerveFactory.SwerveCorner.FRONT_RIGHT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(7, SwerveFactory.SwerveCorner.BACK_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(1, SwerveFactory.SwerveCorner.BACK_RIGHT)));
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_LEFT, SwerveFactory.SwerveCorner.FRONT_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_RIGHT, SwerveFactory.SwerveCorner.FRONT_RIGHT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_LEFT, SwerveFactory.SwerveCorner.BACK_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_RIGHT, SwerveFactory.SwerveCorner.BACK_RIGHT)));
break;

case SIM:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import edu.wpi.first.math.geometry.Rotation2d;
import org.team1540.robot2024.Constants;
import static org.team1540.robot2024.Constants.SwerveConfig.CAN_BUS;;

public class SwerveFactory {
private static final double[] moduleOffsetsRots = new double[]{
Expand All @@ -23,7 +23,7 @@ public class SwerveFactory {
};

public static SwerveModuleHW getModuleMotors(int id, SwerveCorner corner) {
return new SwerveModuleHW(id, corner, Constants.Drivetrain.CAN_BUS);
return new SwerveModuleHW(id, corner, CAN_BUS);
}

public enum SwerveCorner {
Expand Down

0 comments on commit a6ef3da

Please sign in to comment.