Skip to content

Robot Configuration

Lucas Bubner edited this page May 1, 2025 · 10 revisions

The RobotConfig Class

Once you've installed BunyipsLib onto your codebase and familiarised yourself with the Paradigms, you will need to create what effectively is a configuration file for your robot. This file serves as a way for your code to find all your physical components, like motors, servos, cameras, etc. Your configuration class will be referenced throughout all of your OpModes, and should initialise, configure, and set up any robot hardware functions you wish to use.

This paradigm is known as RobotHardware in FTC.

Important

Don't forget to properly configure a Robot Configuration with the Driver Station. The config file for your robot here should effectively mirror the saved configuration. More info here.

Sample RobotConfig classes are provided below. It is used by creating a file that extends RobotConfig.

Various strategies of RobotConfig exist, including hardware-only (public fields declaring hardware only), hardware + subsystem (public fields declaring hardware as an inner class and access to subsystems), and subsystem-only (only exposing encapsulated subsystems). These levels of encapsulation determine how much code and surface area on your config class should be exposed for use in your OpModes. In modern BunyipsLib, the hardware + subsystem approach is recommended.

Note

These are very simple examples of RobotConfig! Chances are that you will be continually expanding, modifying, and changing around this file to accommodate for the settings and preferences you want your hardware to act. These examples are dedicated to showing the structure of a RobotConfig.

Hardware + subsystem declaration (recommended)

Public field exposure of an inner Hardware class, with top-level fields exposing various subsystems.

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;

import au.edu.sa.mbhs.studentrobotics.bunyipslib.RobotConfig;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.hardware.Motor;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.DualServos;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.HoldableActuator;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.drive.SimpleMecanumDrive;

/**
 * An example config, using a subsystem and hardware declaration.
 *
 * @author Your Name Here, YYYY
 */
public class Robot extends RobotConfig {
    /**
     * Hardware instances.
     */
    public final Hardware hw = new Hardware();

    /**
     * Mecanum Drive
     */
    public SimpleMecanumDrive drive;
    /**
     * Vertical lift
     */
    public HoldableActuator lift;
    /**
     * Claw servos
     */
    public DualServos claws;

    @Override
    protected void onRuntime() {
        // Standard hardware configurations (example)
        hw.fl = getHardware("fl", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.REVERSE);
            d.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        });
        hw.bl = getHardware("bl", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.REVERSE);
            d.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        });
        hw.fr = getHardware("fr", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.FORWARD);
            d.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        });
        hw.br = getHardware("br", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.FORWARD);
            d.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
        });
        hw.verticalLift = getHardware("va", Motor.class, (d) -> d.setDirection(DcMotorSimple.Direction.REVERSE));
        hw.leftClaw = getHardware("lc", Servo.class, (d) -> {
            d.setDirection(Servo.Direction.REVERSE);
            d.scaleRange(0.5, 1.0);
        });
        hw.rightClaw = getHardware("rc", Servo.class, (d) -> d.scaleRange(0.0, 0.5));

        // Now assign public subsystems based on the hardware which can also be accessed through the hw object
        drive = new SimpleMecanumDrive(hw.fl, hw.bl, hw.br, hw.fr);
        lift = new HoldableActuator(hw.verticalLift);
        claws = new DualServos(hw.leftClaw, hw.rightClaw);
    }

    /**
     * Definition of all hardware on the robot.
     */
    public static class Hardware {
        /**
         * Control 0: fr
         */
        public DcMotorEx fr;

        /**
         * Control 1: fl
         */
        public DcMotorEx fl;

        /**
         * Control 2: bl
         */
        public DcMotorEx bl;

        /**
         * Control 3: br
         */
        public DcMotorEx br;

        /**
         * Expansion 1: va
         */
        public Motor verticalLift;

        /**
         * Control Servo 2: lc
         */
        public Servo leftClaw;

        /**
         * Control Servo 1: rc
         */
        public Servo rightClaw;
    }
}

Hardware-only declaration

Only hardware is exposed as public fields - subsystems are created at the OpMode level.

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.Servo;

import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.murraybridgebunyips.bunyipslib.RobotConfig;

/**
 * An example config, using a legacy hardware-only declaration.
 *
 * @author Your Name Here, YYYY
 */
public class ExampleConfig extends RobotConfig {
    // It is highly recommended to write down the ports of the hardware as Javadoc comments, as
    // they can sometimes be deleted from the robot either accidentally or mismanaged by someone.
    /**
     * USB: Webcam "webcam"
     */
    public WebcamName webcam;

    /**
     * Control 0: front_left
     */
    public DcMotorEx front_left;

    /**
     * Control 1: front_right
     */
    public DcMotorEx front_right;

    /**
     * Control 2: back_left
     */
    public DcMotorEx back_left;

    /**
     * Control 3: back_right
     */
    public DcMotorEx back_right;

    /**
     * Expansion 0: arm
     */
    public DcMotorEx arm;

    /**
     * Control Servo 0: left_claw
     */
    public Servo left_claw;

    /**
     * Control Servo 1: right_claw
     */
    public Servo right_claw;

    @Override
    protected void onRuntime() {
        // This is where all the variables we just declared are assigned to actual physical components.

        // The string in here should be the name that the component is assigned in the driver hub.
        front_left = getHardware("front_left", DcMotorEx.class, (d) -> {
            // This is where you change settings based on your needs for each component
            // For example, this team needs their front left wheel to have a reversed direction
            // These will differ based on your team's needs and your robot's build.
            d.setDirection(DcMotorSimple.Direction.REVERSE);
        });
        front_right = getHardware("front_right", DcMotorEx.class, (d) -> {
            // These lambda functions passing `d` will only run if the hardware was found therefore no unexpected
            // NullPointerExceptions can be thrown here.
            d.setDirection(DcMotorSimple.Direction.REVERSE);
        });
        back_left = getHardware("back_left", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.REVERSE);
        });
        back_right = getHardware("back_right", DcMotorEx.class, (d) -> {
            d.setDirection(DcMotorSimple.Direction.REVERSE);
        });

        arm = getHardware("arm", DcMotorEx.class, (d) -> {
            // You should familiarise yourself with the standard operations of the DcMotor, including ZeroPowerBehaviour.
            // This can be found in the FTC docs.
            d.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
            d.setDirection(DcMotorSimple.Direction.REVERSE);
        });

        // Defining servos.
        left_claw = getHardware("left_claw", Servo.class);
        // Depending on your hardware, you may need to set the range at which the servo goes manually.
        right_claw = getHardware("right_claw", Servo.class, (d) -> d.scaleRange(0.2, 1.0));
    }
}

Subsystem-only declaration

Raw hardware objects are kept private and are only exposed through subsystems.

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Servo;

import au.edu.sa.mbhs.studentrobotics.bunyipslib.RobotConfig;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.DualServos;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.HoldableActuator;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.subsystems.drive.SimpleMecanumDrive;

/**
 * An example config, using a subsystem-only declaration.
 *
 * @author Your Name Here, YYYY
 */
public class Robot extends RobotConfig {
    /**
     * Mecanum Drive
     */
    public SimpleMecanumDrive drive;
    /**
     * Vertical lift
     */
    public HoldableActuator lift;
    /**
     * Claw servos
     */
    public DualServos claws;

    @Override
    protected void onRuntime() {
        // We store references to hardware at a local scope and then pass them to the subsystems
        // You can use the same techniques from the previous sections to configure directions, etc with null safety
        // using the getHardware util.
        DcMotor frontLeft = getHardware("frontLeft", DcMotor.class);
        DcMotor backLeft = getHardware("backLeft", DcMotor.class);
        DcMotor backRight = getHardware("backRight", DcMotor.class);
        DcMotor frontRight = getHardware("frontRight", DcMotor.class);

        DcMotor liftMotor = getHardware("lift", DcMotor.class);

        Servo left = getHardware("left", Servo.class);
        Servo right = getHardware("right", Servo.class);

        drive = new SimpleMecanumDrive(frontLeft, frontRight, backLeft, backRight);
        lift = new HoldableActuator(liftMotor);
        claws = new DualServos(left, right);
    }
}

Warning

If you try to call getHardware on a device that doesn't exist, a warning will be displayed on the Driver Station at runtime. This will not crash your OpMode as it usually would (as BunyipsLib will try to handle this exception and continue execution), but it is important to configure these devices properly.

Caution

When defining hardware, you must put the object as a class member AND initialise it in the onRuntime() method. Your hardware will be null otherwise, so don't forget.

Significance of RobotConfig

Many elements of BunyipsLib are related to the configuration of subsystems and various coefficients. These definitions - if relevant - should be kept in the RobotConfig, and various elements of the Wiki will reference a RobotConfig when referring to configuration aspects.

These include:

  • PID/system controllers
  • RoadRunner coefficients
  • Subsystem configuration
  • Always-init actions

What now?

If your robot is now configured, creating an OpMode is the next step.

Auto-initialisation

To use the RobotConfig, a common pattern is often used:

@TeleOp
public class MyOpMode extends BunyipsOpMode {
    private final Robot robot = new Robot();
    
    @Override
    protected void onInit() {
        robot.init();
        // ...
    }

    @Override
    protected void activeLoop() {
        // ...
    }
}

This pattern gets quite repetitive, especially over several OpModes. A solution introduced in BunyipsLib v7.0.0 with the new classpath utilities allowing auto-initialisation.

Tip

Use whichever pattern is most comfortable for you. Some may prefer the auto-initialisation of a static instance or using the above strategy. Each is a good way.

Some configuration of your RobotConfig object will be required to use auto-initialisation. For Kotlin users, this is as simple as changing your RobotConfig class into an object, which will allow you to use a singleton pattern. For Java users, you will need to declare a public static final instance of your class (name is your choosing) which will be the instance to initialise.

public class Robot extends RobotConfig {
    public static final instance = new Robot(); // Required for auto-initialisation. The name can be whatever you'd like.    

    @Override
    protected void onRuntime() {
        // ...
    }
}

This instance will be how you access your initialised robot object. You may wish to assign it to a variable (like robot from the conventional method) if that works easier than having to write Robot.instance before every RobotConfig access (private final Robot robot = Robot.instance;).

The next step is as simple as affixing @RobotConfig.AutoInit to your RobotConfig class!

@RobotConfig.AutoInit
public class Robot extends RobotConfig {
    // ...
}

Auto-initialisation is now active for all OpModes. Accessing a fully initialised instance of your robot in any of your OpModes now can be accomplished by accessing Robot.instance.

@TeleOp
public class MyOpMode extends BunyipsOpMode {
    // no initialisation required!
    // as mentioned previously, you can assign a private field here if you still want to use the variable semantics,
    // however, initialising this variable is no longer needed.

    @Override
    protected void activeLoop() {
        Robot.instance.drive.setPower(Controls.vel(gamepad1.lsx, gamepad1.lsy, gamepad1.lsx));
        Robot.instance.drive.update(); // Tip! BunyipsSubsystem.updateAll(); will update all constructed subsystems in the current OpMode
    }
}

Note

RobotConfig's auto-initialisation occurs as a PRE_INIT priority level 2 @Hook.

Sometimes, it is desired that auto-initialisation be inhibited for an OpMode, especially if you don't want your onRuntime method executing for a certain OpMode. To inhibit auto-initialisation, it is simple as annotating the desired OpMode class with @RobotConfig.InhibitAutoInit.

@TeleOp
@RobotConfig.InhibitAutoInit
public class MyAutoInitInhibitedOpMode extends OpMode { // can be any OpMode type
    // ... auto-init will not run for this opmode even if it is enabled in your RobotConfig instance
}

Warning

Inhibiting auto-initialisation will make all of your hardware fields in Robot.instance null. Note you can manually call Robot.instance.init() if you'd like.

Caution

Attaching @Config to your RobotConfig instance may cause the class to not show up on the dashboard, as it will try to recursively add itself to the config. To combat this you will need to use inner static or an entirely different class to hold your constants.

@RobotConfig.AutoInit
public class Robot extends RobotConfig {
   @Config
   public static class Constants {
       public static double SOME_CONSTANT = 1;
       // ...
   }
   
   public static Robot instance = new Robot();
   // ...
}

Examples across the wiki do not show auto-initialisation to make it clear on the initialisation of a RobotConfig object, however, all examples that do use RobotConfig can be used with this paradigm.

Review the extensive API documentation for further information regarding auto-initialisation, and review the Classpath scanning utilities section for more information regarding the @Hook.

Clone this wiki locally