Skip to content

Commit

Permalink
Set up switch of constants based on RoboRIO Serial code
Browse files Browse the repository at this point in the history
Co-Authored-By: Aceius E. <144858100+AceiusRedshift@users.noreply.github.com>
  • Loading branch information
MichaelLesirge and AceiusRedshift committed Jan 31, 2024
1 parent 63cc0a2 commit b181789
Show file tree
Hide file tree
Showing 3 changed files with 93 additions and 25 deletions.
1 change: 1 addition & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
"Brushless",
"Deadzone",
"Odometry",
"Robo",
"setpoint",
"teleop",
"teleoperated"
Expand Down
116 changes: 91 additions & 25 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,27 +10,33 @@
* Do not put any functionality in this class.
*/
public final class Constants {
// Bot-specific constants.
public static final String SOME_VALUE; // This is a demo/test constant
public static enum Bot { WOOD_BOT, PRACTICE_BOT, COMPETITION_BOT }

public static final Bot currentBot;

/**
* This code determines what bot is being deployed and sets constants accordingly.
*
* Simulated bots cannot have a RoboRIO ID, so we must check if the bot is real. If it isn't, load production config.
* The production bot is always default, so if we do anything crazy to our bot during the tourney like swich the roborio the code works.
* The production bot is always default, so if we do anything crazy to our bot during the tourney like switch the RoboRIO the code works.
*
* @author Aceius E.
*/
static {
String serialNumber = RobotBase.isReal() ? RobotController.getSerialNumber() : "default";
final String serialNumber = RobotBase.isReal() ? RobotController.getSerialNumber() : "default";

switch (serialNumber) {
case "03282B00": // Wood Bot
SOME_VALUE = "Wood Bot Value";
case "03282B00": // Wood Bot Serial Number
currentBot = Bot.WOOD_BOT;
break;

default: // Production Bot
SOME_VALUE = "Comp Bot Value";

case "1": // Practice Bot Serial Number
currentBot = Bot.PRACTICE_BOT;
break;

case "2": // Competition Bot Serial Number

This comment has been minimized.

Copy link
@AceiusRedshift

AceiusRedshift Feb 1, 2024

Author Member

Clarify that these are placeholders for the actual roborio ids

default: // Also use competition bot as default
currentBot = Bot.COMPETITION_BOT;
break;
}
}
Expand Down Expand Up @@ -76,6 +82,66 @@ public static class OperatorConstants {
}

public static class SwerveModuleConstants {

static { switch (currentBot) {
case WOOD_BOT:
// Front Left
VELOCITY_MOTOR_ID_FL = 41;
ANGULAR_MOTOR_ID_FL = 40;
ANGULAR_MOTOR_ENCODER_ID_FL = 1;
ANGULAR_MOTOR_ENCODER_OFFSET_FL = -0.611328125;

// Front right
VELOCITY_MOTOR_ID_FR = 4;
ANGULAR_MOTOR_ID_FR = 5;
ANGULAR_MOTOR_ENCODER_ID_FR = 2;
ANGULAR_MOTOR_ENCODER_OFFSET_FR = -0.282958;

// Back left
VELOCITY_MOTOR_ID_BL = 3;
ANGULAR_MOTOR_ID_BL = 2;
ANGULAR_MOTOR_ENCODER_ID_BL = 4;
ANGULAR_MOTOR_ENCODER_OFFSET_BL = -0.9260253906;

// Back right
VELOCITY_MOTOR_ID_BR = 42;
ANGULAR_MOTOR_ID_BR = 6;
ANGULAR_MOTOR_ENCODER_ID_BR = 3;
ANGULAR_MOTOR_ENCODER_OFFSET_BR = -0.8641367187;
break;

case PRACTICE_BOT:
default: // Temporary default to practice bot
// Front Left
VELOCITY_MOTOR_ID_FL = 41;
ANGULAR_MOTOR_ID_FL = 40;
ANGULAR_MOTOR_ENCODER_ID_FL = 1;
ANGULAR_MOTOR_ENCODER_OFFSET_FL = -0.611328125;

// Front right
VELOCITY_MOTOR_ID_FR = 4;
ANGULAR_MOTOR_ID_FR = 5;
ANGULAR_MOTOR_ENCODER_ID_FR = 2;
ANGULAR_MOTOR_ENCODER_OFFSET_FR = -0.282958;

// Back left
VELOCITY_MOTOR_ID_BL = 3;
ANGULAR_MOTOR_ID_BL = 2;
ANGULAR_MOTOR_ENCODER_ID_BL = 4;
ANGULAR_MOTOR_ENCODER_OFFSET_BL = -0.9260253906;

// Back right
VELOCITY_MOTOR_ID_BR = 42;
ANGULAR_MOTOR_ID_BR = 6;
ANGULAR_MOTOR_ENCODER_ID_BR = 3;
ANGULAR_MOTOR_ENCODER_OFFSET_BR = -0.8641367187;
break;

// case COMPETITION_BOT:
// default:

// break;
}}

// Values from https://www.swervedrivespecialties.com/products/mk4-swerve-module. We have L1 Modules.
public static final double DRIVE_MOTOR_GEAR_RATIO = 1 / 8.4;
Expand All @@ -100,28 +166,28 @@ public static class SwerveModuleConstants {
public static final double STEERING_PID_D = 0;

// Front left
public static final int VELOCITY_MOTOR_ID_FL = 41;
public static final int ANGULAR_MOTOR_ID_FL = 40;
public static final int ANGULAR_MOTOR_ENCODER_ID_FL = 1;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_FL = -0.611328125;
public static final int VELOCITY_MOTOR_ID_FL;
public static final int ANGULAR_MOTOR_ID_FL;
public static final int ANGULAR_MOTOR_ENCODER_ID_FL;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_FL;

// Front right
public static final int VELOCITY_MOTOR_ID_FR = 4;
public static final int ANGULAR_MOTOR_ID_FR = 5;
public static final int ANGULAR_MOTOR_ENCODER_ID_FR = 2;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_FR = -0.282958;
public static final int VELOCITY_MOTOR_ID_FR;
public static final int ANGULAR_MOTOR_ID_FR;
public static final int ANGULAR_MOTOR_ENCODER_ID_FR;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_FR;

// Back left
public static final int VELOCITY_MOTOR_ID_BL = 3;
public static final int ANGULAR_MOTOR_ID_BL = 2;
public static final int ANGULAR_MOTOR_ENCODER_ID_BL = 4;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_BL = -0.9260253906;
public static final int VELOCITY_MOTOR_ID_BL;
public static final int ANGULAR_MOTOR_ID_BL;
public static final int ANGULAR_MOTOR_ENCODER_ID_BL;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_BL;

// Back right
public static final int VELOCITY_MOTOR_ID_BR = 42;
public static final int ANGULAR_MOTOR_ID_BR = 6;
public static final int ANGULAR_MOTOR_ENCODER_ID_BR = 3;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_BR = -0.8641367187;
public static final int VELOCITY_MOTOR_ID_BR;
public static final int ANGULAR_MOTOR_ID_BR;
public static final int ANGULAR_MOTOR_ENCODER_ID_BR;
public static final double ANGULAR_MOTOR_ENCODER_OFFSET_BR;
}

public static class SwerveDrivetrainConstants {
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ public void setUpDriveController() {
final HIDType genericHIDType = genericHID.getType();

SmartDashboard.putString("Drive Controller", genericHIDType.toString());
SmartDashboard.putString("Bot Name", Constants.currentBot.name());

if (genericHIDType.equals(GenericHID.HIDType.kHIDJoystick)) {
final CommandJoystick driverJoystick = new CommandJoystick(genericHID.getPort());
Expand Down

1 comment on commit b181789

@AceiusRedshift
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LOOKS GOOD 👍

Please sign in to comment.