Skip to content

Java Example: Build an Auto

Michael Jansen edited this page Nov 2, 2023 · 4 revisions

In PathPlannerLib, autos are created using the PathPlannerAuto class. This class is essentially just a command group that will build itself based on an auto file created in the GUI. Therefore, you can use PathPlannerAuto just like any other command, i.e add to a SendableChooser, bind to a button, etc.

Before creating an auto, you must first configure the AutoBuilder, so that the auto is able to build itself with the correct path following command and settings.

Configuring AutoBuilder

There are a few options for configuring AutoBuilder, one for each type of path following command: Holonomic, Ramsete, and LTV. Since all of the AutoBuilder configuration is related to the drive subsystem, it is recommended to configure AutoBuilder at the end of your drive subsystem's constructor. NOTE: You can only configure AutoBuilder once. An exception will be thrown if you try to configure it multiple times.

Holonomic

public SwerveSubsystem(){
    // Do all subsystem initialization here
    // ...

    // Configure the AutoBuilder last
    AutoBuilder.configureHolonomic(
        this::getPose, // Robot pose supplier
        this::resetPose, // Method to reset odometry (will be called if your auto has a starting pose)
        this::getRobotRelativeSpeeds, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
        this::driveRobotRelative, // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds
        new HolonomicPathFollowerConfig( // HolonomicPathFollowerConfig, this should likely live in your Constants class
            new PIDConstants(5.0, 0.0, 0.0), // Translation PID constants
            new PIDConstants(5.0, 0.0, 0.0), // Rotation PID constants
            4.5, // Max module speed, in m/s
            0.4, // Drive base radius in meters. Distance from robot center to furthest module.
            new ReplanningConfig() // Default path replanning config. See the API for the options here
        ),
        this // Reference to this subsystem to set requirements
    );
}

Ramsete

This example will use the default Ramsete configuration. If you would like to customize the b and zeta terms, there is another AutoBuilder configuration method with that option.

public DriveSubsystem(){
    // Do all subsystem initialization here
    // ...

    // Configure the AutoBuilder last
    AutoBuilder.configureRamsete(
        this::getPose, // Robot pose supplier
        this::resetPose, // Method to reset odometry (will be called if your auto has a starting pose)
        this::getCurrentSpeeds, // Current ChassisSpeeds supplier
        this::drive, // Method that will drive the robot given ChassisSpeeds
        new ReplanningConfig(), // Default path replanning config. See the API for the options here
        this // Reference to this subsystem to set requirements
    );
}

LTV

This example will use the default LTV configuration. If you would like to customize the qelems and relems terms, there is another AutoBuilder configuration method with that option.

public DriveSubsystem(){
    // Do all subsystem initialization here
    // ...

    // Configure the AutoBuilder last
    AutoBuilder.configureLTV(
        this::getPose, // Robot pose supplier
        this::resetPose, // Method to reset odometry (will be called if your auto has a starting pose)
        this::getCurrentSpeeds, // Current ChassisSpeeds supplier
        this::drive, // Method that will drive the robot given ChassisSpeeds
        0.02, // Robot control loop period in seconds. Default is 0.02
        new ReplanningConfig(), // Default path replanning config. See the API for the options here
        this // Reference to this subsystem to set requirements
    );
}

Create an Auto

After you have configured the AutoBuilder, creating an auto is as simple as constructing a PathPlannerAuto with the name of the auto you made in the GUI.

public Command getAutonomousCommand(){
    return new PathPlannerAuto("Example Auto");
}

Build a SendableChooser with all Autos in project

After configuring the AutoBuilder, you have the option to build a SendableChooser that is automatically populated with every auto in the project.

private final SendableChooser<Command> autoChooser;

public RobotContainer() {
    // ... other init + AutoBuilder configuration

    // Build an auto chooser. This will use Commands.none() as the default option.
    autoChooser = AutoBuilder.buildAutoChooser();

    // Another option that allows you to specify the default auto by its name
    // autoChooser = AutoBuilder.buildAutoChooser("My Default Auto");

    SmartDashboard.putData("Auto Chooser", autoChooser);
}

public Command getAutonomousCommand() {
    return autoChooser.getSelected();
}
Clone this wiki locally