Class Choreo

java.lang.Object
com.choreo.lib.Choreo

public class Choreo extends Object
Utilities to load and follow ChoreoTrajectories
  • Constructor Details

    • Choreo

      public Choreo()
      Default constructor.
  • Method Details

    • getTrajectory

      public static ChoreoTrajectory getTrajectory(String trajName)
      Load a trajectory from the deploy directory. Choreolib expects .traj files to be placed in src/main/deploy/choreo/[trajName].traj .
      Parameters:
      trajName - the path name in Choreo, which matches the file name in the deploy directory. Do not include ".traj" here.
      Returns:
      the loaded trajectory, or null if the trajectory could not be loaded.
    • getTrajectoryGroup

      public static ArrayList<ChoreoTrajectory> getTrajectoryGroup(String trajName)
      Loads the split parts of the specified trajectory. Fails and returns null if any of the parts could not be loaded.

      This method determines the number of parts to load by counting the files that match the pattern "trajName.X.traj", where X is a string of digits. Let this count be N. It then attempts to load "trajName.1.traj" through "trajName.N.traj", consecutively counting up. If any of these files cannot be loaded, the method returns null.

      Parameters:
      trajName - The path name in Choreo for this trajectory.
      Returns:
      The ArrayList of segments, in order, or null.
    • choreoSwerveCommand

      public static Command choreoSwerveCommand(ChoreoTrajectory trajectory, Supplier<Pose2d> poseSupplier, PIDController xController, PIDController yController, PIDController rotationController, Consumer<ChassisSpeeds> outputChassisSpeeds, BooleanSupplier mirrorTrajectory, Subsystem... requirements)
      Create a command to follow a Choreo path.
      Parameters:
      trajectory - The trajectory to follow. Use Choreo.getTrajectory(String trajName) to load this from the deploy directory.
      poseSupplier - A function that returns the current field-relative pose of the robot.
      xController - A PIDController for field-relative X translation (input: X error in meters, output: m/s).
      yController - A PIDController for field-relative Y translation (input: Y error in meters, output: m/s).
      rotationController - A PIDController for robot rotation (input: heading error in radians, output: rad/s). This controller will have its continuous input range set to -pi..pi by ChoreoLib.
      outputChassisSpeeds - A function that consumes the target robot-relative chassis speeds and commands them to the robot.
      mirrorTrajectory - If this returns true, the path will be mirrored to the opposite side, while keeping the same coordinate system origin. This will be called every loop during the command.
      requirements - The subsystem(s) to require, typically your drive subsystem only.
      Returns:
      A command that follows a Choreo path.
    • choreoSwerveCommand

      public static Command choreoSwerveCommand(ChoreoTrajectory trajectory, Supplier<Pose2d> poseSupplier, ChoreoControlFunction controller, Consumer<ChassisSpeeds> outputChassisSpeeds, BooleanSupplier mirrorTrajectory, Subsystem... requirements)
      Create a command to follow a Choreo path.
      Parameters:
      trajectory - The trajectory to follow. Use Choreo.getTrajectory(String trajName) to load this from the deploy directory.
      poseSupplier - A function that returns the current field-relative pose of the robot.
      controller - A ChoreoControlFunction to follow the current trajectory state. Use ChoreoCommands.choreoSwerveController(PIDController xController, PIDController yController, PIDController rotationController) to create one using PID controllers for each degree of freedom. You can also pass in a function with the signature (Pose2d currentPose, ChoreoTrajectoryState referenceState) -> ChassisSpeeds to implement a custom follower (i.e. for logging).
      outputChassisSpeeds - A function that consumes the target robot-relative chassis speeds and commands them to the robot.
      mirrorTrajectory - If this returns true, the path will be mirrored to the opposite side, while keeping the same coordinate system origin. This will be called every loop during the command.
      requirements - The subsystem(s) to require, typically your drive subsystem only.
      Returns:
      A command that follows a Choreo path.
    • choreoSwerveController

      public static ChoreoControlFunction choreoSwerveController(PIDController xController, PIDController yController, PIDController rotationController)
      Creates a control function for following a ChoreoTrajectoryState.
      Parameters:
      xController - A PIDController for field-relative X translation (input: X error in meters, output: m/s).
      yController - A PIDController for field-relative Y translation (input: Y error in meters, output: m/s).
      rotationController - A PIDController for robot rotation (input: heading error in radians, output: rad/s). This controller will have its continuous input range set to -pi..pi by ChoreoLib.
      Returns:
      A ChoreoControlFunction to track ChoreoTrajectoryStates. This function returns robot-relative ChassisSpeeds.