Package swervelib
Class SwerveController
java.lang.Object
swervelib.SwerveController
Controller class used to convert raw inputs into robot speeds.
-
Field Summary
FieldsModifier and TypeFieldDescriptionedu.wpi.first.math.filter.SlewRateLimiterSlewRateLimiterfor angular movement in radians/second.SwerveControllerConfigurationobject storing data to generate thePIDControllerfor controlling the robot heading, and deadband for heading joystick.doubleLast angle as a scalar [-1,1] the robot was set to.private final edu.wpi.first.math.controller.PIDControllerPID Controller for the robot heading.edu.wpi.first.math.filter.SlewRateLimiterSlewRateLimiterfor movement in the X direction in meters/second.edu.wpi.first.math.filter.SlewRateLimiterSlewRateLimiterfor movement in the Y direction in meters/second. -
Constructor Summary
ConstructorsConstructorDescriptionConstruct the SwerveController object which is used for determining the speeds of the robot based on controller input. -
Method Summary
Modifier and TypeMethodDescriptionvoidaddSlewRateLimiters(edu.wpi.first.math.filter.SlewRateLimiter x, edu.wpi.first.math.filter.SlewRateLimiter y, edu.wpi.first.math.filter.SlewRateLimiter angle) Add slew rate limiters to all controls.edu.wpi.first.math.kinematics.ChassisSpeedsgetRawTargetSpeeds(double xSpeed, double ySpeed, double omega) Get theChassisSpeedsbased of raw speeds desired in meters/second and heading in radians.edu.wpi.first.math.kinematics.ChassisSpeedsgetRawTargetSpeeds(double xSpeed, double ySpeed, double targetHeadingAngleRadians, double currentHeadingAngleRadians) Get theChassisSpeedsbased of raw speeds desired in meters/second and heading in radians.edu.wpi.first.math.kinematics.ChassisSpeedsgetTargetSpeeds(double xInput, double yInput, double angle, double currentHeadingAngleRadians) Get the chassis speeds based on controller input of 1 joystick [-1,1] and an angle.edu.wpi.first.math.kinematics.ChassisSpeedsgetTargetSpeeds(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.Translation2dgetTranslation2d(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Helper function to get theTranslation2dof the chassis speeds given theChassisSpeeds.doubleheadingCalculate(double currentHeadingAngleRadians, double targetHeadingAngleRadians) Calculate the angular velocity given the current and target heading angle in radians.booleanwithinHypotDeadband(double x, double y) Calculate the hypot deadband and check if the joystick is within it.
-
Field Details
-
config
SwerveControllerConfigurationobject storing data to generate thePIDControllerfor controlling the robot heading, and deadband for heading joystick. -
thetaController
private final edu.wpi.first.math.controller.PIDController thetaControllerPID Controller for the robot heading. -
lastAngleScalar
public double lastAngleScalarLast angle as a scalar [-1,1] the robot was set to. -
xLimiter
public edu.wpi.first.math.filter.SlewRateLimiter xLimiterSlewRateLimiterfor movement in the X direction in meters/second. -
yLimiter
public edu.wpi.first.math.filter.SlewRateLimiter yLimiterSlewRateLimiterfor movement in the Y direction in meters/second. -
angleLimiter
public edu.wpi.first.math.filter.SlewRateLimiter angleLimiterSlewRateLimiterfor angular movement in radians/second.
-
-
Constructor Details
-
SwerveController
Construct the SwerveController object which is used for determining the speeds of the robot based on controller input.- Parameters:
cfg-SwerveControllerConfigurationcontaining the PIDF variables for the heading PIDF.
-
-
Method Details
-
getTranslation2d
public static edu.wpi.first.math.geometry.Translation2d getTranslation2d(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Helper function to get theTranslation2dof the chassis speeds given theChassisSpeeds.- Parameters:
speeds- Chassis speeds.- Returns:
Translation2dof the speed the robot is going in.
-
addSlewRateLimiters
public void addSlewRateLimiters(edu.wpi.first.math.filter.SlewRateLimiter x, edu.wpi.first.math.filter.SlewRateLimiter y, edu.wpi.first.math.filter.SlewRateLimiter angle) Add slew rate limiters to all controls. This prevents the robot from ramping up too much. To disable aSlewRateLimiterset the desired one to null.- Parameters:
x- TheSlewRateLimiterfor the X velocity in meters/second.y- TheSlewRateLimiterfor the Y velocity in meters/second.angle- TheSlewRateLimiterfor the angular velocity in radians/second.
-
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.- Returns:
- Whether the values are within the deadband from
SwerveControllerConfiguration.angleJoyStickRadiusDeadband.
-
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 [-1,1] and an 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:
ChassisSpeedswhich 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:
ChassisSpeedswhich can be sent to th Swerve Drive.
-
getRawTargetSpeeds
public edu.wpi.first.math.kinematics.ChassisSpeeds getRawTargetSpeeds(double xSpeed, double ySpeed, double omega) Get theChassisSpeedsbased of raw speeds desired in meters/second and heading in radians.- Parameters:
xSpeed- X speed in meters per second.ySpeed- Y speed in meters per second.omega- Angular velocity in radians/second.- Returns:
ChassisSpeedsthe robot should move to.
-
getRawTargetSpeeds
public edu.wpi.first.math.kinematics.ChassisSpeeds getRawTargetSpeeds(double xSpeed, double ySpeed, double targetHeadingAngleRadians, double currentHeadingAngleRadians) Get theChassisSpeedsbased of raw speeds desired in meters/second and heading in radians.- Parameters:
xSpeed- X speed in meters per second.ySpeed- Y speed in meters per second.targetHeadingAngleRadians- Target heading in radians.currentHeadingAngleRadians- Current heading in radians.- Returns:
ChassisSpeedsthe robot should move to.
-
headingCalculate
public double headingCalculate(double currentHeadingAngleRadians, double targetHeadingAngleRadians) Calculate the angular velocity given the current and target heading angle in radians.- Parameters:
currentHeadingAngleRadians- The current heading of the robot in radians.targetHeadingAngleRadians- The target heading of the robot in radians.- Returns:
- Angular velocity in radians per second.
-