Class SwerveController


  • public class SwerveController
    extends Object
    Controller class used to convert raw inputs into robot speeds.
    • Constructor Summary

      Constructors 
      Constructor Description
      SwerveController​(SwerveControllerConfiguration cfg)
      Construct the SwerveController object which is used for determining the speeds of the robot based on controller input.
    • Method Summary

      All Methods Static Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      edu.wpi.first.math.kinematics.ChassisSpeeds getTargetSpeeds​(double xInput, double yInput, double angle, double currentHeadingAngleRadians)
      Get the chassis speeds based on controller input of 1 joystick and a angle.
      edu.wpi.first.math.kinematics.ChassisSpeeds getTargetSpeeds​(double xInput, double yInput, double headingX, double headingY, double currentHeadingAngleRadians)
      Get the chassis speeds based on controller input of 2 joysticks.
      static edu.wpi.first.math.geometry.Translation2d getTranslation2d​(edu.wpi.first.math.kinematics.ChassisSpeeds speeds)
      Helper function to get the Translation2d of the chassis speeds given the ChassisSpeeds.
      boolean withinHypotDeadband​(double x, double y)
      Calculate the hypot deadband and check if the joystick is within it.
    • Field Detail

      • thetaController

        private final edu.wpi.first.math.controller.PIDController thetaController
        PID Controller for the robot heading.
      • lastAngle

        public double lastAngle
        Last angle to robot was set to.
    • Constructor Detail

      • SwerveController

        public SwerveController​(SwerveControllerConfiguration cfg)
        Construct the SwerveController object which is used for determining the speeds of the robot based on controller input.
    • Method Detail

      • getTranslation2d

        public static edu.wpi.first.math.geometry.Translation2d getTranslation2d​(edu.wpi.first.math.kinematics.ChassisSpeeds speeds)
        Helper function to get the Translation2d of the chassis speeds given the ChassisSpeeds.
        Parameters:
        speeds - Chassis speeds.
        Returns:
        Translation2d of the speed the robot is going in.
      • withinHypotDeadband

        public boolean withinHypotDeadband​(double x,
                                           double y)
        Calculate the hypot deadband and check if the joystick is within it.
        Parameters:
        x - The x value for the joystick in which the deadband should be applied.
        y - The y value for the joystick in which the deadband should be applied.
      • getTargetSpeeds

        public edu.wpi.first.math.kinematics.ChassisSpeeds getTargetSpeeds​(double xInput,
                                                                           double yInput,
                                                                           double angle,
                                                                           double currentHeadingAngleRadians)
        Get the chassis speeds based on controller input of 1 joystick and a angle.
        Parameters:
        xInput - X joystick input for the robot to move in the X direction.
        yInput - Y joystick input for the robot to move in the Y direction.
        angle - The desired angle of the robot in radians.
        currentHeadingAngleRadians - The current robot heading in radians.
        Returns:
        ChassisSpeeds which can be sent to th Swerve Drive.
      • getTargetSpeeds

        public edu.wpi.first.math.kinematics.ChassisSpeeds getTargetSpeeds​(double xInput,
                                                                           double yInput,
                                                                           double headingX,
                                                                           double headingY,
                                                                           double currentHeadingAngleRadians)
        Get the chassis speeds based on controller input of 2 joysticks. One for speeds in which direction. The other for the angle of the robot.
        Parameters:
        xInput - X joystick input for the robot to move in the X direction.
        yInput - Y joystick input for the robot to move in the Y direction.
        headingX - X joystick which controls the angle of the robot.
        headingY - Y joystick which controls the angle of the robot.
        currentHeadingAngleRadians - The current robot heading in radians.
        Returns:
        ChassisSpeeds which can be sent to th Swerve Drive.