Class RobotConfig

java.lang.Object
com.pathplanner.lib.config.RobotConfig

public class RobotConfig extends Object
Configuration class describing everything that needs to be known about the robot to generate trajectories
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final boolean
    Is the robot holonomic?
    final double
    The mass of the robot, including bumpers and battery, in KG
    final double
    The maximum torque a drive module can apply without slipping the wheels
    The drive module config
    Robot-relative locations of each drive module in meters
    final double[]
    The distance from the robot center to each module in meters
    final double
    The moment of inertia of the robot, in KG*M^2
    final int
    Number of drive modules
    final double
    The force of static friction between the robot's drive wheels and the carpet, in Newtons
  • Constructor Summary

    Constructors
    Constructor
    Description
    RobotConfig(double massKG, double MOI, ModuleConfig moduleConfig, double trackwidthMeters)
    Create a robot config object for a DIFFERENTIAL DRIVE robot
    RobotConfig(double massKG, double MOI, ModuleConfig moduleConfig, double trackwidthMeters, double wheelbaseMeters)
    Create a robot config object for a HOLONOMIC DRIVE robot
    RobotConfig(edu.wpi.first.units.measure.Mass mass, edu.wpi.first.units.measure.MomentOfInertia MOI, ModuleConfig moduleConfig, edu.wpi.first.units.measure.Distance trackwidthMeters)
    Create a robot config object for a DIFFERENTIAL DRIVE robot
    RobotConfig(edu.wpi.first.units.measure.Mass mass, edu.wpi.first.units.measure.MomentOfInertia MOI, ModuleConfig moduleConfig, edu.wpi.first.units.measure.Distance trackwidthMeters, edu.wpi.first.units.measure.Distance wheelbaseMeters)
    Create a robot config object for a HOLONOMIC DRIVE robot
  • Method Summary

    Modifier and Type
    Method
    Description
    Convert chassis forces (passed as ChassisSpeeds) to individual wheel force vectors
    Load the robot config from the shared settings file created by the GUI
    Convert an array of swerve module states to robot-relative chassis speeds.
    Convert robot-relative chassis speeds to an array of swerve module states.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • massKG

      public final double massKG
      The mass of the robot, including bumpers and battery, in KG
    • MOI

      public final double MOI
      The moment of inertia of the robot, in KG*M^2
    • moduleConfig

      public final ModuleConfig moduleConfig
      The drive module config
    • moduleLocations

      public final Translation2d[] moduleLocations
      Robot-relative locations of each drive module in meters
    • isHolonomic

      public final boolean isHolonomic
      Is the robot holonomic?
    • numModules

      public final int numModules
      Number of drive modules
    • modulePivotDistance

      public final double[] modulePivotDistance
      The distance from the robot center to each module in meters
    • wheelFrictionForce

      public final double wheelFrictionForce
      The force of static friction between the robot's drive wheels and the carpet, in Newtons
    • maxTorqueFriction

      public final double maxTorqueFriction
      The maximum torque a drive module can apply without slipping the wheels
  • Constructor Details

    • RobotConfig

      public RobotConfig(double massKG, double MOI, ModuleConfig moduleConfig, double trackwidthMeters, double wheelbaseMeters)
      Create a robot config object for a HOLONOMIC DRIVE robot
      Parameters:
      massKG - The mass of the robot, including bumpers and battery, in KG
      MOI - The moment of inertia of the robot, in KG*M^2
      moduleConfig - The drive module config
      trackwidthMeters - The distance between the left and right side of the drivetrain, in meters
      wheelbaseMeters - The distance between the front and back side of the drivetrain, in meters
    • RobotConfig

      public RobotConfig(edu.wpi.first.units.measure.Mass mass, edu.wpi.first.units.measure.MomentOfInertia MOI, ModuleConfig moduleConfig, edu.wpi.first.units.measure.Distance trackwidthMeters, edu.wpi.first.units.measure.Distance wheelbaseMeters)
      Create a robot config object for a HOLONOMIC DRIVE robot
      Parameters:
      mass - The mass of the robot, including bumpers and battery
      MOI - The moment of inertia of the robot
      moduleConfig - The drive module config
      trackwidthMeters - The distance between the left and right side of the drivetrain
      wheelbaseMeters - The distance between the front and back side of the drivetrain
    • RobotConfig

      public RobotConfig(double massKG, double MOI, ModuleConfig moduleConfig, double trackwidthMeters)
      Create a robot config object for a DIFFERENTIAL DRIVE robot
      Parameters:
      massKG - The mass of the robot, including bumpers and battery, in KG
      MOI - The moment of inertia of the robot, in KG*M^2
      moduleConfig - The drive module config
      trackwidthMeters - The distance between the left and right side of the drivetrain, in meters
    • RobotConfig

      public RobotConfig(edu.wpi.first.units.measure.Mass mass, edu.wpi.first.units.measure.MomentOfInertia MOI, ModuleConfig moduleConfig, edu.wpi.first.units.measure.Distance trackwidthMeters)
      Create a robot config object for a DIFFERENTIAL DRIVE robot
      Parameters:
      mass - The mass of the robot, including bumpers and battery
      MOI - The moment of inertia of the robot
      moduleConfig - The drive module config
      trackwidthMeters - The distance between the left and right side of the drivetrain
  • Method Details

    • toSwerveModuleStates

      public SwerveModuleState[] toSwerveModuleStates(ChassisSpeeds speeds)
      Convert robot-relative chassis speeds to an array of swerve module states. This will use differential kinematics for diff drive robots, then convert the wheel speeds to module states.
      Parameters:
      speeds - Robot-relative chassis speeds
      Returns:
      Array of swerve module states
    • toChassisSpeeds

      public ChassisSpeeds toChassisSpeeds(SwerveModuleState[] states)
      Convert an array of swerve module states to robot-relative chassis speeds. This will use differential kinematics for diff drive robots.
      Parameters:
      states - Array of swerve module states
      Returns:
      Robot-relative chassis speeds
    • chassisForcesToWheelForceVectors

      public Translation2d[] chassisForcesToWheelForceVectors(ChassisSpeeds chassisForces)
      Convert chassis forces (passed as ChassisSpeeds) to individual wheel force vectors
      Parameters:
      chassisForces - The linear X/Y force and torque acting on the whole robot
      Returns:
      Array of individual wheel force vectors
    • fromGUISettings

      public static RobotConfig fromGUISettings() throws IOException, org.json.simple.parser.ParseException
      Load the robot config from the shared settings file created by the GUI
      Returns:
      RobotConfig matching the robot settings in the GUI
      Throws:
      IOException - if an I/O error occurs
      org.json.simple.parser.ParseException - if a JSON parsing error occurs