Package robot.swerve
Class SwerveSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
robot.swerve.SwerveSubsystem
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable,edu.wpi.first.wpilibj2.command.Subsystem
public class SwerveSubsystem
extends edu.wpi.first.wpilibj2.command.SubsystemBase
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoidedu.wpi.first.wpilibj2.command.Commandc_controlRotation(DoubleSupplier getTheta) edu.wpi.first.wpilibj2.command.Commandc_driveFieldRelative(double x, double y, double theta) Hold a field-relative movement speed and rotation speed.edu.wpi.first.wpilibj2.command.Commandc_driveFieldRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Hold a field-relative movement speed and rotation speed.edu.wpi.first.wpilibj2.command.Commandc_driveRobotRelative(double x, double y, double theta) Hold a robot-relative movement speed and rotation speed.edu.wpi.first.wpilibj2.command.Commandc_driveRobotRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Hold a robot-relative movement speed and rotation speed.edu.wpi.first.wpilibj2.command.Commandedu.wpi.first.wpilibj2.command.Commandc_gotoPose(Supplier<? extends edu.wpi.first.math.geometry.Pose2d> getPose, boolean useAbsoluteHeading) Combination ofc_rotateToandc_gotoPos.edu.wpi.first.wpilibj2.command.Commandc_input(Supplier<? extends edu.wpi.first.math.geometry.Translation2d> translation, DoubleSupplier theta) Drive according to inputs provided by the suppliers.edu.wpi.first.wpilibj2.command.Commandc_rotateTo(double theta, boolean useAbsoluteHeading) edu.wpi.first.wpilibj2.command.Commandc_rotateTo(Supplier<Double> getTheta, boolean useAbsoluteHeading) edu.wpi.first.wpilibj2.command.Commandc_stop()Stop the wheels.voiddriveFieldRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive relative to the field.voiddriveRobotRelative(double x, double y, double theta) voiddriveRobotRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive relative to the current angle of the robot.voiddriveRobotRelative(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Drive relative to the current angle of the robot.voidflipZero()Flip current zero position by 180deg.edu.wpi.first.math.kinematics.ChassisSpeedsedu.wpi.first.math.kinematics.SwerveModuleState[]edu.wpi.first.math.geometry.Pose2dedu.wpi.first.math.geometry.Translation2dedu.wpi.first.math.geometry.Translation2dvoidinitSendable(edu.wpi.first.util.sendable.SendableBuilder builder) voidinput(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive according to joystick inputs.voidperiodic()booleanvoidvoidsetAutoBrickWhenStill(boolean enabled) voidsetMotorBrake(boolean brake) voidstartPoseEstimator(edu.wpi.first.math.geometry.Pose2d currentPose) voidstartPoseEstimator(edu.wpi.first.math.geometry.Translation2d currentPos) voidstop()voidedu.wpi.first.math.geometry.Translation2dtoRobotRelative(edu.wpi.first.math.geometry.Translation2d translation) voidzero()Zero the rotation encoders for all swerve modules.Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, setName, setSubsystemMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, idle, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
-
Constructor Details
-
SwerveSubsystem
-
-
Method Details
-
getModuleStates
public edu.wpi.first.math.kinematics.SwerveModuleState[] getModuleStates() -
startPoseEstimator
public void startPoseEstimator(edu.wpi.first.math.geometry.Translation2d currentPos) -
startPoseEstimator
public void startPoseEstimator(edu.wpi.first.math.geometry.Pose2d currentPose) -
stopPoseEstimator
public void stopPoseEstimator() -
poseEstimatorEnabled
public boolean poseEstimatorEnabled() -
getPoseEstimate
public edu.wpi.first.math.geometry.Pose2d getPoseEstimate()- Returns:
- The current pose estimate, based on swerve odometry and
addVisionPoseEstimate()calls
-
getPositionEstimate
public edu.wpi.first.math.geometry.Translation2d getPositionEstimate()- Returns:
- The current position estimate, equivalent to
getPoseEstimate().getTranslation()
-
getChassisSpeeds
public edu.wpi.first.math.kinematics.ChassisSpeeds getChassisSpeeds()- Returns:
- current robot-relative
ChassisSpeeds(velocity and direction) according to encoders
-
getVelocity
public edu.wpi.first.math.geometry.Translation2d getVelocity()- Returns:
- current robot-relative velocity according to encoders
-
input
public void input(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive according to joystick inputs.hypot(x, y)should not exceed 1.- Parameters:
translation- X/Y movement from [-1, 1], wpilib coordinate system (forward, left)theta- Turn speed from [-1, 1], positive = counterclockwise
-
toRobotRelative
public edu.wpi.first.math.geometry.Translation2d toRobotRelative(edu.wpi.first.math.geometry.Translation2d translation) -
driveFieldRelative
public void driveFieldRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive relative to the field.- Parameters:
translation- Movement speed in meters per secondtheta- Rotation speed in rotations per second - not field-relative, as it represents the turning speed, not an absolute angle. Will be overridden if a c_rotateTo() command is active
-
driveRobotRelative
public void driveRobotRelative(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Drive relative to the current angle of the robot.- Parameters:
speeds- Target velocity and rotation, deconstructed into a translation and rotation. SeedriveRobotRelative(Translation2d, double)
-
driveRobotRelative
public void driveRobotRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Drive relative to the current angle of the robot.- Parameters:
translation- Movement speed in meters per second Will be overridden if ac_gotoPos()command is activetheta- Rotation speed in rotations per second. Will be overridden if ac_rotateTo()command is active
-
driveRobotRelative
public void driveRobotRelative(double x, double y, double theta) -
stop
public void stop() -
periodic
public void periodic() -
c_rotateTo
public edu.wpi.first.wpilibj2.command.Command c_rotateTo(double theta, boolean useAbsoluteHeading) - Parameters:
theta- Field-relative angle to rotate touseAbsoluteHeading- Whentrue, flips the IMU angle when on red alliance. This makes the angles "properly" field-relative instead of "alliance-relative"- Returns:
- A command that uses PID to rotate to the provided angle. Overrides any rotation from any other drive commands or methods while the command is running
-
c_rotateTo
public edu.wpi.first.wpilibj2.command.Command c_rotateTo(Supplier<Double> getTheta, boolean useAbsoluteHeading) - Parameters:
getTheta- Supplier of field-relative angles to rotate touseAbsoluteHeading- Whentrue, flips the IMU angle when on red alliance. This makes the angles "properly" field-relative instead of "alliance-relative"- Returns:
- A command that uses PID to rotate to the provided angle. Overrides any rotation from any other drive commands or methods while the command is running
-
c_controlRotation
- Parameters:
getTheta- Supplies doubles representing the difference between the current heading and target angle- Returns:
- A command that uses PID to rotate to the provided angle. Overrides any rotation from any other drive commands or methods while the command is running
-
c_gotoPos
public edu.wpi.first.wpilibj2.command.Command c_gotoPos(Supplier<edu.wpi.first.math.geometry.Translation2d> getPos) - Parameters:
getPos- Supplier of field-relative translations to go to. Returnnullto signal that the last pose was the final pose of the path, and the command will end once the robot is withinPositionCommand.DISTANCE_THRESHOLDof the final pose.- Returns:
- A command that uses PID and the
pose estimatorto follow a stream of positions. Overrides any movement from any other drive commands or methods while the command is running
-
c_gotoPose
public edu.wpi.first.wpilibj2.command.Command c_gotoPose(Supplier<? extends edu.wpi.first.math.geometry.Pose2d> getPose, boolean useAbsoluteHeading) Combination ofc_rotateToandc_gotoPos. -
c_stop
public edu.wpi.first.wpilibj2.command.Command c_stop()Stop the wheels. -
c_driveFieldRelative
public edu.wpi.first.wpilibj2.command.Command c_driveFieldRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Hold a field-relative movement speed and rotation speed. -
c_driveFieldRelative
public edu.wpi.first.wpilibj2.command.Command c_driveFieldRelative(double x, double y, double theta) Hold a field-relative movement speed and rotation speed. -
c_driveRobotRelative
public edu.wpi.first.wpilibj2.command.Command c_driveRobotRelative(edu.wpi.first.math.geometry.Translation2d translation, double theta) Hold a robot-relative movement speed and rotation speed. -
c_driveRobotRelative
public edu.wpi.first.wpilibj2.command.Command c_driveRobotRelative(double x, double y, double theta) Hold a robot-relative movement speed and rotation speed. -
c_input
public edu.wpi.first.wpilibj2.command.Command c_input(Supplier<? extends edu.wpi.first.math.geometry.Translation2d> translation, DoubleSupplier theta) Drive according to inputs provided by the suppliers. -
resetOdometry
public void resetOdometry() -
zero
public void zero()Zero the rotation encoders for all swerve modules. -
flipZero
public void flipZero()Flip current zero position by 180deg. -
setMotorBrake
public void setMotorBrake(boolean brake) -
brickMode
public void brickMode() -
setAutoBrickWhenStill
public void setAutoBrickWhenStill(boolean enabled) -
initSendable
public void initSendable(edu.wpi.first.util.sendable.SendableBuilder builder) - Specified by:
initSendablein interfaceedu.wpi.first.util.sendable.Sendable- Overrides:
initSendablein classedu.wpi.first.wpilibj2.command.SubsystemBase
-