Swap between different configuration files in one place

Hello Java programmers, I was wondering what solutions you have for easily swapping configurations/constants files. We currently just have one Constants.java file, but this year we are building multiple robots, including a dedicated code testing bot (:smile: ). Each one of these bots has different device IDs, swerve steering encoder offsets, and other configuration that varies between each bot. We also have some configuration that is consistent between all bots. We want to be able to swap configuration from a single place, preferably somewhere in RobotContainer.java.

The current hacky solution I can think of is having one universal Constants.java file, and then a RobotConstants.java file that contains the robot specific stuff, and renaming the other RobotConstants.java files to RobotConstantsUnused1.java, but obviously this not ideal and very annoying to do.

We currently have a Constants file that looks something like this:

package frc.robot;

import edu.wpi.first.math.util.Units;

/**
 * Use Constants as convenient to hold robot-wide numerical or boolean constants.
 * All constants should be visible globally (public), not be on the instance (static), and should be not change (final).
 * Do not put any functionality in this class.
 */
public final class Constants {

    public static class DriverConstants {
        public static final double JOYSTICK_DEAD_ZONE = 0.15;

        // Some other stuff that is the same between all robots...
    }

    public static class SwerveModuleConstants {
    
      // Front left swerve module
      public static final int ANGULAR_MOTOR_ID_FL = 41;
      public static final int VELOCITY_MOTOR_ID_FL = 4
      public static final int ANGULAR_MOTOR_ENCODER_ID_FL = 1;
      public static final double ANGULAR_MOTOR_ENCODER_OFFSET_FL = 0;

     // Other encoder values, pid values, offsets, etc...

    }

   // A bunch of other stuff. Some that change, some that does not....
}

I would try to make the configs as similar as possible. That means changing the CAN IDs and other stuff. PID values and stuff may still need to be different, but you should try to minimize these differences.

Now for the question you askedā€¦ there is a Preferences class you can use instead of the Constants class in your project. If you really wanted to get fancy, you could use preferences, but fall back to the constants if the value doesnā€™t exist. Alternatively, you could deploy files in whatever format you prefer (json, yaml, properties, xml, etc), then parse it at initialization. If you include multiple files (one for each bot), then its just a matter of telling your code which file to read (either hardcoded or through preferences)

our code reads the serial number of the roborio and selects configuration based on that. we use an enum to represent the roborio identity:

we use the identity enum to guide the robot construction like this:

hope this helps!

1 Like

A few years ago we built two robots and plugged a small breaker in one of the DIO on the roboRIO on one of the robots. On startup we read the status of that DIO port and determined whether itā€™s robot A or robot B.

We use the roboRIO comments. Used to read the file and Peter Johnson told us the shortcut here on CD. Hereā€™s an example of switching between 2 robots.

package frc.robot;

import java.lang.invoke.MethodHandles;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.RobotController;
import frc.robot.subsystems.DrivetrainConfig;
import frc.robot.subsystems.SwerveModuleConfig;

public final class Constants
{
    // This string gets the full name of the class, including the package name
    private static final String fullClassName = MethodHandles.lookup().lookupClass().getCanonicalName();
    private static String Robot4237 = "";

    public static double DRIVETRAIN_WHEELBASE_METERS  ; 
    public static double DRIVETRAIN_TRACKWIDTH_METERS ; 

    // *** STATIC INITIALIZATION BLOCK ***
    // This block of code is run first when the class is loaded
    static
    {
        System.out.println("Loading: " + fullClassName);

        String comment = RobotController.getComments();
        System.out.println("The roboRIO comment is >" + comment + "<");
      
        // Use the comment variable to decide what to do
        if(comment.contains("2023 Robot"))
        {
            Robot4237 = "2023 Robot";
            Constants.DRIVETRAIN_WHEELBASE_METERS =  27.44 * DrivetrainConstants.INCHES_TO_METERS; // 23.5 Front to back
            Constants.DRIVETRAIN_TRACKWIDTH_METERS = 19.50 * DrivetrainConstants.INCHES_TO_METERS; // 23.5 // Side to side
            
        }
        else if (comment.contains("2022 Robot"))
        { 
            Robot4237 = "2022 Robot";
            Constants.DRIVETRAIN_WHEELBASE_METERS =  23.5 * DrivetrainConstants.INCHES_TO_METERS; // Front to back
            Constants.DRIVETRAIN_TRACKWIDTH_METERS = 23.5 * DrivetrainConstants.INCHES_TO_METERS; // Side to side
        }
        else 
        {
            System.out.println("Unknown Robot " + comment);
        }

        System.out.println("Robot:" + Robot4237);

    }
    
    private static final String CANIVORE = "CANivore";
    private static final String ROBORIO = "rio";

    public static class Drivetrain
    {
        private static final int FRONT_LEFT_DRIVE       = 7;
        private static final int FRONT_LEFT_ENCODER     = 8;  
        private static final int FRONT_LEFT_TURN        = 9;  

        private static final int FRONT_RIGHT_DRIVE      = 10;
        private static final int FRONT_RIGHT_ENCODER    = 11;  
        private static final int FRONT_RIGHT_TURN       = 12;  

        private static final int BACK_LEFT_DRIVE        = 4; 
        private static final int BACK_LEFT_ENCODER      = 5; 
        private static final int BACK_LEFT_TURN         = 6;  

        private static final int BACK_RIGHT_DRIVE       = 1; 
        private static final int BACK_RIGHT_ENCODER     = 2; 
        private static final int BACK_RIGHT_TURN        = 3;

        public static final String CANCODER_CAN_BUS = CANIVORE;
        public static final String MOTOR_CAN_BUS = ROBORIO;
    }

    public static class PowerDistributionHub
    {
        public static final int PDH_CAN_ID              = 1;

        public static final String CAN_BUS = ROBORIO;
    }

    public static class Gyro 
    {
        public static final int PIGEON_ID = 0;

        // public static final AxisDirection FORWARD_AXIS = AxisDirection.PositiveX;
        // public static final AxisDirection UP_AXIS = AxisDirection.PositiveZ;

        public static final double RESET_GYRO_DELAY = 0.1;
        public static final String PIGEON_CAN_BUS = CANIVORE;
    }

    public static class Controller
    {
        public static final int DRIVER = 0;
        public static final int OPERATOR = 1;
    }

    public static class DrivetrainConstants
    {
        static
        {
            System.out.println("Loading: " + MethodHandles.lookup().lookupClass().getCanonicalName());
        }       
        public static final double INCHES_TO_METERS = 0.0254;
        // public static final double DRIVETRAIN_WHEELBASE_METERS =  27.44 * INCHES_TO_METERS; // 23.5 Front to back
        // public static final double DRIVETRAIN_TRACKWIDTH_METERS = 19.50 * INCHES_TO_METERS; // 23.5 // Side to side
        public static final double MAX_MODULE_TURN_SPEED = 1080.0; // degrees per second, this is 3.0 rev/sec, used to be 1980 and 5.5 rev/sec
        public static final double MAX_MODULE_TURN_ACCELERATION = 1728.0; // degrees per second per second, this is 4.8 rev/sec^2, used to be 17280 and 48 rev/sec^2
        public static final double MAX_BATTERY_VOLTAGE = 12.0;
        public static final int DRIVE_MOTOR_ENCODER_RESOLUTION = 42;
        public static final double DRIVE_MOTOR_GEAR_RATIO = 8.14;
        public static final double WHEEL_RADIUS_METERS = 2.0 * INCHES_TO_METERS;
        public static final double DRIVE_ENCODER_RATE_TO_METERS_PER_SEC = 
            ((10.0 / DRIVE_MOTOR_ENCODER_RESOLUTION) / DRIVE_MOTOR_GEAR_RATIO) * (2.0 * Math.PI * WHEEL_RADIUS_METERS);
        public static final double DRIVE_ENCODER_POSITION_TO_METERS =
            ((1.0 / DRIVE_MOTOR_ENCODER_RESOLUTION) / DRIVE_MOTOR_GEAR_RATIO) * (2.0 * Math.PI * WHEEL_RADIUS_METERS);
        public static final double MAX_DRIVE_SPEED = 4.4; // meters per second

        public static double DRIVETRAIN_WHEELBASE_METERS = Constants.DRIVETRAIN_WHEELBASE_METERS  ; // 23.5 Front to back
        public static double DRIVETRAIN_TRACKWIDTH_METERS = Constants.DRIVETRAIN_TRACKWIDTH_METERS ; // 23.5 // Side to side

        public static final double X_ACCELERATION_RATE_LIMT = 10.0;
        public static final double X_DECELERATION_RATE_LIMT = 10.0;
        public static final double Y_ACCELERATION_RATE_LIMT = 10.0;
        public static final double Y_DECELERATION_RATE_LIMT = 10.0;
    }

    public static class SwerveModuleSetup
    {
        private static double FRONT_LEFT_ENCODER_OFFSET   ;
        private static double FRONT_RIGHT_ENCODER_OFFSET  ;
        private static double BACK_LEFT_ENCODER_OFFSET    ;
        private static double BACK_RIGHT_ENCODER_OFFSET   ;

        private static final Translation2d FRONT_LEFT_LOCATION = new Translation2d(Constants.DRIVETRAIN_WHEELBASE_METERS / 2, Constants.DRIVETRAIN_TRACKWIDTH_METERS / 2);
        private static final Translation2d FRONT_RIGHT_LOCATION = new Translation2d(Constants.DRIVETRAIN_WHEELBASE_METERS / 2, -Constants.DRIVETRAIN_TRACKWIDTH_METERS / 2);
        private static final Translation2d BACK_LEFT_LOCATION = new Translation2d(-Constants.DRIVETRAIN_WHEELBASE_METERS / 2, Constants.DRIVETRAIN_TRACKWIDTH_METERS / 2);
        private static final Translation2d BACK_RIGHT_LOCATION = new Translation2d(-Constants.DRIVETRAIN_WHEELBASE_METERS / 2, -Constants.DRIVETRAIN_TRACKWIDTH_METERS / 2);
       
        static
        {
            System.out.println("Loading: " + MethodHandles.lookup().lookupClass().getCanonicalName());

            if(Robot4237.equals("2023 Robot"))
            {
                FRONT_LEFT_ENCODER_OFFSET   = -209.883; 
                FRONT_RIGHT_ENCODER_OFFSET  = -171.562; //-133.330; changed at state 
                BACK_LEFT_ENCODER_OFFSET    = -18.809; 
                BACK_RIGHT_ENCODER_OFFSET   = -342.422; 
            }
            else if (Robot4237.equals("2022 Robot"))
            {
                FRONT_LEFT_ENCODER_OFFSET   = -0.282715;//-102.129; //-338.730;
                FRONT_RIGHT_ENCODER_OFFSET  = -0.374756;//-135.088; //-287.578;
                BACK_LEFT_ENCODER_OFFSET    = -0.979736;//-352.529; //-348.75;
                BACK_RIGHT_ENCODER_OFFSET   = -0.041260;//-15.205;  //-103.271;
            }
            else 
            {
                System.out.println("Unknown Robot " + Robot4237);
            }
        }
        
        public static final SwerveModuleConfig FRONT_LEFT = new SwerveModuleConfig(
            "Front Left", FRONT_LEFT_LOCATION, Drivetrain.FRONT_LEFT_DRIVE, true, Drivetrain.FRONT_LEFT_ENCODER, FRONT_LEFT_ENCODER_OFFSET, Drivetrain.FRONT_LEFT_TURN);
        public static final SwerveModuleConfig FRONT_RIGHT = new SwerveModuleConfig(
            "Front Right", FRONT_RIGHT_LOCATION, Drivetrain.FRONT_RIGHT_DRIVE, false, Drivetrain.FRONT_RIGHT_ENCODER, FRONT_RIGHT_ENCODER_OFFSET, Drivetrain.FRONT_RIGHT_TURN);
        public static final SwerveModuleConfig BACK_LEFT = new SwerveModuleConfig(
            "Back Left", BACK_LEFT_LOCATION, Drivetrain.BACK_LEFT_DRIVE, true, Drivetrain.BACK_LEFT_ENCODER, BACK_LEFT_ENCODER_OFFSET, Drivetrain.BACK_LEFT_TURN);
        public static final SwerveModuleConfig BACK_RIGHT = new SwerveModuleConfig(
            "Back Right", BACK_RIGHT_LOCATION, Drivetrain.BACK_RIGHT_DRIVE, false, Drivetrain.BACK_RIGHT_ENCODER, BACK_RIGHT_ENCODER_OFFSET, Drivetrain.BACK_RIGHT_TURN); 
    }

    public static class DrivetrainSetup
    {
        static
        {
        System.out.println("Loading: " + MethodHandles.lookup().lookupClass().getCanonicalName());
        }
        public static final DrivetrainConfig DRIVETRAIN_DATA = new DrivetrainConfig(
            SwerveModuleSetup.FRONT_LEFT, SwerveModuleSetup.FRONT_RIGHT, SwerveModuleSetup.BACK_LEFT, SwerveModuleSetup.BACK_RIGHT);
    }

    public static class Camera
    {
        public static final int translationXMetersIndex = 0;
        public static final int translationYMetersIndex = 1;
        public static final int translationZMetersIndex = 2;
        public static final int rotationRollDegreesIndex = 3;
        public static final int rotationPitchDegreesIndex = 4;
        public static final int rotationYawDegreesIndex = 5;
        public static final int totalLatencyIndex = 6;
    }
}

In 3061-lib, we take the approach of having a RobotConfig abstract class that is extended by a config-specific file for each robot. We create the appropriate config object based on the robot specified in the Constants class. This occurs at the very start of the RobotContainer constructor. We then invoke the static getInstance method on the RobotConfig class to get a reference to the current robotā€™s config object on which to query properties (example).

In all of these approaches, and in whatever case you are considering, I highly recommend having the ā€œdefaultā€ or ā€œcanā€™t identify which robotā€ case fall back to your competition configuration.

That way, if there are any last-minute deployments to the competition robot, even if there are some bugs or you had to do something crazy like swap out a RIO between matches and didnā€™t have time to set some flags, everything will still work.

1 Like