Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Multiple Robot Support #24

Open
wants to merge 9 commits into
base: main
Choose a base branch
from
11 changes: 11 additions & 0 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
{
"image": "mcr.microsoft.com/devcontainers/universal:2",
"postCreateCommand": "cd /opt && wget 'https://github.com/wpilibsuite/vscode-wpilib/releases/download/v2024.3.1/vscode-wpilib-2024.3.1.vsix'",
"features": {
},
"customizations": {
"vscode": {
"extensions": ["/opt/vscode-wpilib-2024.3.1.vsix","vscjava.vscode-java-pack","vscjava.vscode-gradle"]
}
}
}
21 changes: 15 additions & 6 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,20 +18,29 @@ public final class Constants {

public static enum Robot {
COMPETITION,
PRACTICE
PRACTICE,
SIMBOT
}

public static enum RobotMode {
public static enum RobotEnvironment {
REAL,
SIMULATED,
REPLAYED
}

public static final Robot ROBOT = Robot.COMPETITION; // The robot currently running.
public static final boolean REPLAYING = false; // Should the simulation start into replay mode when not running on the RIO?
public static final boolean SAVE_SIMULATED_LOGS = false; // Should the physics simulation mode save a .wpilog?
// The robot currently running. Change to simbot to use simulation.
public static final Robot ROBOT = Robot.COMPETITION;

// Check to see if configured robot is configured incorrectly for the runtime.
static {
if (RobotBase.isReal() && ROBOT == Robot.SIMBOT) {
throw new RuntimeException("Invalid Configuration! Robot set to simulation on real bot!");
}
}

public static final RobotEnvironment ENVIRONMENT = RobotBase.isReal() ? RobotEnvironment.REAL : (ROBOT == Robot.SIMBOT ? RobotEnvironment.SIMULATED : RobotEnvironment.REPLAYED);

public static final RobotMode ROBOT_MODE = RobotBase.isReal() ? RobotMode.REAL : (REPLAYING ? RobotMode.REPLAYED : RobotMode.SIMULATED);
public static final boolean SAVE_SIMULATED_LOGS = false; // Should the physics simulation mode save a .wpilog?

public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ public void robotInit() {
}

// Set up data flow
switch (Constants.ROBOT_MODE) {
switch (Constants.ENVIRONMENT) {
case REAL:
Logger.addDataReceiver(new WPILOGWriter());
Logger.addDataReceiver(new NT4Publisher());
Expand Down Expand Up @@ -84,7 +84,7 @@ public void robotInit() {
break;
}

Logger.recordMetadata("Environment", Constants.ROBOT_MODE.toString());
Logger.recordMetadata("Environment", Constants.ENVIRONMENT.toString());

// Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the "Understanding Data Flow" page
Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may be added.
Expand Down
45 changes: 39 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,11 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants.OperatorConstants;
import frc.robot.Constants.RobotEnvironment;
import frc.robot.commands.drive.TeleopSwerveDrive;
import frc.robot.generated.CompSwerveConstants;
import frc.robot.subsystems.IntakeShooter.IntakeShooterIOHardware;
import frc.robot.subsystems.IntakeShooter.IntakeShooterSubsystem;
import frc.robot.subsystems.Swerve.SwerveIO;
import frc.robot.subsystems.Swerve.SwerveIOCTRE;
import frc.robot.subsystems.Swerve.SwerveSubsystem;
import frc.robot.subsystems.oi.OISubsystem;

Expand All @@ -31,16 +32,48 @@ public class RobotContainer {
new CommandXboxController(OperatorConstants.kDriverControllerPort);

// Subsystems

private final SwerveSubsystem drivetrain_ = new SwerveSubsystem(CompSwerveConstants.DriveTrain);

private final IntakeShooterSubsystem intake_shooter_ =
new IntakeShooterSubsystem(new IntakeShooterIOHardware());
// Init with default implementations in case robot is configured wrongly or is in replay. This will be overitten later.
private SwerveSubsystem drivetrain_ = new SwerveSubsystem(new SwerveIO() {});

private final OISubsystem oiPanel_ = new OISubsystem(OperatorConstants.kOperatorInterfacePort);

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {

// Set up real subsystems based on the runtime environment.
if (Constants.ENVIRONMENT != RobotEnvironment.REPLAYED) {
switch (Constants.ROBOT) {
case COMPETITION -> {
drivetrain_ = new SwerveSubsystem(new SwerveIOCTRE(
CompSwerveConstants.DrivetrainConstants,
CompSwerveConstants.FrontLeft,
CompSwerveConstants.FrontRight,
CompSwerveConstants.BackLeft,
CompSwerveConstants.BackRight
));
}
case PRACTICE -> {
drivetrain_ = new SwerveSubsystem(new SwerveIOCTRE(
CompSwerveConstants.DrivetrainConstants,
CompSwerveConstants.FrontLeft,
CompSwerveConstants.FrontRight,
CompSwerveConstants.BackLeft,
CompSwerveConstants.BackRight
)); // Change for other tuner constants when they are generated.
}
case SIMBOT -> {
drivetrain_ = new SwerveSubsystem(new SwerveIOCTRE(
CompSwerveConstants.DrivetrainConstants,
CompSwerveConstants.FrontLeft,
CompSwerveConstants.FrontRight,
CompSwerveConstants.BackLeft,
CompSwerveConstants.BackRight
)); // Should auto simulate.
}
}
}

// Configure the trigger bindings
configureBindings();
setupDrivetrain();
Expand Down
13 changes: 5 additions & 8 deletions src/main/java/frc/robot/generated/CompSwerveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory;

import edu.wpi.first.math.util.Units;
import frc.robot.subsystems.Swerve.SwerveIOCTRE;

// Generated by the Tuner X Swerve Project Generator
// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
Expand Down Expand Up @@ -83,7 +82,7 @@ public class CompSwerveConstants {
private static final double kSteerFrictionVoltage = 0.25;
private static final double kDriveFrictionVoltage = 0.25;

private static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
.withCANbusName(kCANbusName)
.withPigeon2Id(kPigeonId)
.withPigeon2Configs(pigeonConfigs);
Expand Down Expand Up @@ -147,15 +146,13 @@ public class CompSwerveConstants {
private static final double kBackRightYPosInches = -11.375;


private static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants(
public static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset, Units.inchesToMeters(kFrontLeftXPosInches), Units.inchesToMeters(kFrontLeftYPosInches), kInvertLeftSide);
private static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants(
public static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset, Units.inchesToMeters(kFrontRightXPosInches), Units.inchesToMeters(kFrontRightYPosInches), kInvertRightSide);
private static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants(
public static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset, Units.inchesToMeters(kBackLeftXPosInches), Units.inchesToMeters(kBackLeftYPosInches), kInvertLeftSide);
private static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants(
public static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants(
kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset, Units.inchesToMeters(kBackRightXPosInches), Units.inchesToMeters(kBackRightYPosInches), kInvertRightSide);

public static final SwerveIOCTRE DriveTrain = new SwerveIOCTRE(DrivetrainConstants, FrontLeft,
FrontRight, BackLeft, BackRight);
}
30 changes: 21 additions & 9 deletions src/main/java/frc/robot/subsystems/Swerve/SwerveIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,20 @@ public interface SwerveIO {

@AutoLog
public static class SwerveIOInputs {
public SwerveModuleState[] moduleStates = new SwerveModuleState[4];
public SwerveModuleState[] moduleTargetStates = new SwerveModuleState[4];
public SwerveModuleState[] moduleStates = {
new SwerveModuleState(),
new SwerveModuleState(),
new SwerveModuleState(),
new SwerveModuleState()
};

public SwerveModuleState[] moduleTargetStates = {
new SwerveModuleState(),
new SwerveModuleState(),
new SwerveModuleState(),
new SwerveModuleState()
};

public Pose2d pose = new Pose2d();
public ChassisSpeeds speeds = new ChassisSpeeds();
public double odometryPeriodSeconds = 0.0;
Expand All @@ -30,16 +42,16 @@ public static class SwerveIOInputs {
public boolean odometryIsValid = false;
}

public void updateInputs(SwerveIOInputsAutoLogged inputs);
public default void updateInputs(SwerveIOInputsAutoLogged inputs) {};

public void setOperatorPerspectiveForward(Rotation2d fieldDirection);
public default void setOperatorPerspectiveForward(Rotation2d fieldDirection) {};

public void setControl(SwerveRequest request);
public default void setControl(SwerveRequest request) {};

public void seedFieldRelative(Pose2d pose2d);
public void seedFieldRelative();
public default void seedFieldRelative(Pose2d pose2d) {};
public default void seedFieldRelative() {};

public void addVisionMeasurement(Pose2d visionMeasurement, double timestampSeconds);
public void addVisionMeasurement(Pose2d visionMeasurement, double timestampSeconds, Matrix<N3, N1> visionMeasurementStdDevs);
public default void addVisionMeasurement(Pose2d visionMeasurement, double timestampSeconds) {};
public default void addVisionMeasurement(Pose2d visionMeasurement, double timestampSeconds, Matrix<N3, N1> visionMeasurementStdDevs) {};

}