Class SwerveSetpointGenerator

java.lang.Object
com.pathplanner.lib.util.swerve.SwerveSetpointGenerator

public class SwerveSetpointGenerator extends Object
Swerve setpoint generator based on a version created by FRC team 254.

Takes a prior setpoint, a desired setpoint, and outputs a new setpoint that respects all the kinematic constraints on module rotation and wheel velocity/torque, as well as preventing any forces acting on a module's wheel from exceeding the force of friction.

  • Constructor Details

    • SwerveSetpointGenerator

      public SwerveSetpointGenerator(RobotConfig config, double maxSteerVelocityRadsPerSec)
      Create a new swerve setpoint generator
      Parameters:
      config - The robot configuration
      maxSteerVelocityRadsPerSec - The maximum rotation velocity of a swerve module, in radians per second
    • SwerveSetpointGenerator

      public SwerveSetpointGenerator(RobotConfig config, edu.wpi.first.units.measure.AngularVelocity maxSteerVelocity)
      Create a new swerve setpoint generator
      Parameters:
      config - The robot configuration
      maxSteerVelocity - The maximum rotation velocity of a swerve module
  • Method Details

    • generateSetpoint

      public SwerveSetpoint generateSetpoint(SwerveSetpoint prevSetpoint, ChassisSpeeds desiredStateRobotRelative, double dt)
      Generate a new setpoint. Note: Do not discretize ChassisSpeeds passed into or returned from this method. This method will discretize the speeds for you.
      Parameters:
      prevSetpoint - The previous setpoint motion. Normally, you'd pass in the previous iteration setpoint instead of the actual measured/estimated kinematic state.
      desiredStateRobotRelative - The desired state of motion, such as from the driver sticks or a path following algorithm.
      dt - The loop time.
      Returns:
      A Setpoint object that satisfies all the kinematic/friction limits while converging to desiredState quickly.