Package frc.team4373.swerve
Class SwerveDrivetrain
- java.lang.Object
-
- edu.wpi.first.wpilibj.command.Subsystem
-
- frc.team4373.swerve.SwerveDrivetrain
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.Sendable
,java.lang.AutoCloseable
public abstract class SwerveDrivetrain extends edu.wpi.first.wpilibj.command.Subsystem
A programmatic representation of a swerve drivetrain.Requirements:
- The robot must be rectangular.
- The robot must be rectangular.
- The motors must use CTRE TalonSRX motor controllers.
- The robot must have a Pigeon IMU.
- The motor controllers and Pigeon must be connected over the CAN bus.
- The motor controlllers must have encoders connected.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
SwerveDrivetrain.BrakeMode
The swerve brake mode for the swerve bot (i.e., what to do when the input is zero).static class
SwerveDrivetrain.DriveMode
The drive mode for the swerve bot.static class
SwerveDrivetrain.WheelID
A programmatic representation of which wheel is being referenced.
-
Field Summary
Fields Modifier and Type Field Description SwerveInputTransform
transform
TheSwerveInputTransform
transform object for this swerve bot.
-
Constructor Summary
Constructors Modifier Constructor Description protected
SwerveDrivetrain(SwerveConfig config)
Creates a new SwerveDrivetrain subclass instance with the given configuration.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
brake()
Sets the wheels to the configured brake configuration if any is selected.void
drive(double rotation, double x, double y)
Drives using the transform for the given parameters.double
getAngle()
Returns the current angle relative to the starting position (mod 360).double
getAverageDriveMotorPosition()
Gets the average of the drive motor positions.SwerveDrivetrain.BrakeMode
getBrakeMode()
Gets the currently selected swerve brake mode.SwerveDrivetrain.DriveMode
getDriveMode()
Gets the current drive mode.double
getDriveMotorPosition(SwerveDrivetrain.WheelID wheelID)
Gets the current position of the drive motor.double
getDriveMotorVelocity(SwerveDrivetrain.WheelID wheelID)
Gets the velocity of the drive motor for the specified wheel.double
getPercentOutput(SwerveDrivetrain.WheelID wheelID)
Gets the percent output of the specified SwerveWheel.double
getPigeonYawRaw()
Returns the raw Pigeon yaw value.double
getRotatorMotorPosition(SwerveDrivetrain.WheelID wheelID)
Gets the position of the rotator motor for the specified wheel.double
getRotatorMotorVelocity(SwerveDrivetrain.WheelID wheelID)
Gets the velocity of the rotator motor for the specified wheel.void
modularizeEncoders()
Resets the encoders to within [-4095, 4095] Call this method in `robotInit` to (almost) eliminate the possibility of accumulator rollover during one power cycle.void
resetEncoder(SwerveDrivetrain.WheelID wheelID)
Resets the position of the rotator encoder of the given wheel.void
resetPigeonYaw()
Resets the pigeon's yaw to consider the current orientation field-forward (zero degrees).void
setBrakeMode(SwerveDrivetrain.BrakeMode brakeMode)
Sets the swerve brake mode.void
setDriveMode(SwerveDrivetrain.DriveMode driveMode)
Sets the swerve drive mode (north- or own-ship-up).void
setMaxWheelAcceleration(double maxAccel)
Sets the max acceleration for each wheel.void
setPID(SwerveDrivetrain.WheelID wheelID, SwerveConfig.PID drivePID, SwerveConfig.PID rotatorPID)
Sets the PID gains for a specified wheel.void
setPigeonYaw(double angle)
Sets the pigeon's yaw to be a given value at the current position.void
setWheelsPercOut(WheelVector.VectorSet vectors)
Sets vectors to the SwerveWheels with a PID setpoint for angle and % output for speed.void
setWheelsPID(WheelVector.VectorSet vectors)
Sets velocity vectors to the four SwerveWheels with PID setpoints for both speed and angle.void
stop()
Stops the robot (i.e., sets outputs of all motors of all wheels to zero).-
Methods inherited from class edu.wpi.first.wpilibj.command.Subsystem
addChild, addChild, close, getCurrentCommand, getCurrentCommandName, getDefaultCommand, getDefaultCommandName, getName, getSubsystem, initDefaultCommand, initSendable, periodic, setDefaultCommand, setName, setSubsystem, toString
-
-
-
-
Field Detail
-
transform
public SwerveInputTransform transform
TheSwerveInputTransform
transform object for this swerve bot.
-
-
Constructor Detail
-
SwerveDrivetrain
protected SwerveDrivetrain(SwerveConfig config)
Creates a new SwerveDrivetrain subclass instance with the given configuration.- Parameters:
config
- the configuration for the new SwerveDrivetrain.
-
-
Method Detail
-
stop
public void stop()
Stops the robot (i.e., sets outputs of all motors of all wheels to zero).
-
drive
public void drive(double rotation, double x, double y)
Drives using the transform for the given parameters.- Parameters:
rotation
- the joystick rotation, in degrees.x
- the x-coordinate, -1 to 1.y
- the y-coordinate, -1 to 1.
-
brake
public void brake()
Sets the wheels to the configured brake configuration if any is selected.
-
setWheelsPID
public void setWheelsPID(WheelVector.VectorSet vectors)
Sets velocity vectors to the four SwerveWheels with PID setpoints for both speed and angle.- Parameters:
vectors
- the four vectors ordered right1, left1, left2, right2.
-
setWheelsPercOut
public void setWheelsPercOut(WheelVector.VectorSet vectors)
Sets vectors to the SwerveWheels with a PID setpoint for angle and % output for speed.- Parameters:
vectors
- the four vectors ordered right1, left1, left2, right2.
-
getAngle
public double getAngle()
Returns the current angle relative to the starting position (mod 360).- Returns:
- the current angle relative to the starting position on the interval [0, 360).
-
getPigeonYawRaw
public double getPigeonYawRaw()
Returns the raw Pigeon yaw value.- Returns:
- Pigeon yaw value.
-
getPercentOutput
public double getPercentOutput(SwerveDrivetrain.WheelID wheelID)
Gets the percent output of the specified SwerveWheel.- Parameters:
wheelID
- the ID of the wheel.- Returns:
- the wheel's percent output, [-1, 1].
-
getDriveMotorPosition
public double getDriveMotorPosition(SwerveDrivetrain.WheelID wheelID)
Gets the current position of the drive motor.- Parameters:
wheelID
- the ID of the wheel whose position to fetch.- Returns:
- the current position in encoder units.
-
getAverageDriveMotorPosition
public double getAverageDriveMotorPosition()
Gets the average of the drive motor positions.- Returns:
- average of drive position in encoder units.
-
getDriveMotorVelocity
public double getDriveMotorVelocity(SwerveDrivetrain.WheelID wheelID)
Gets the velocity of the drive motor for the specified wheel.- Parameters:
wheelID
- the ID of the wheel whose drive velocity to fetch.- Returns:
- the wheel's drive velocity in encoder units.
-
getRotatorMotorPosition
public double getRotatorMotorPosition(SwerveDrivetrain.WheelID wheelID)
Gets the position of the rotator motor for the specified wheel. Since the rotator is a mag encoder, this is an absolute position.- Parameters:
wheelID
- the ID of the wheel whose rotator position to fetch.- Returns:
- the wheel's absolute rotator position in encoder units.
-
getRotatorMotorVelocity
public double getRotatorMotorVelocity(SwerveDrivetrain.WheelID wheelID)
Gets the velocity of the rotator motor for the specified wheel.- Parameters:
wheelID
- the ID of the wheel whose rotator velocity to fetch.- Returns:
- the wheel's rotator velocity in encoder units.
-
setPID
public void setPID(SwerveDrivetrain.WheelID wheelID, SwerveConfig.PID drivePID, SwerveConfig.PID rotatorPID)
Sets the PID gains for a specified wheel.- Parameters:
wheelID
- the wheel whose PID gains to change.drivePID
- aSwerveConfig.PID
object with new parameters for the drive PID, or null to leave unchanged.rotatorPID
- aSwerveConfig.PID
object with parameters for rotational PID, or null to leave unchanged.
-
setDriveMode
public void setDriveMode(SwerveDrivetrain.DriveMode driveMode)
Sets the swerve drive mode (north- or own-ship-up).- Parameters:
driveMode
- theSwerveDrivetrain.DriveMode
to set.
-
getDriveMode
public SwerveDrivetrain.DriveMode getDriveMode()
Gets the current drive mode.- Returns:
- the currently selected
SwerveDrivetrain.DriveMode
.
-
setBrakeMode
public void setBrakeMode(SwerveDrivetrain.BrakeMode brakeMode)
Sets the swerve brake mode.- Parameters:
brakeMode
- theSwerveDrivetrain.BrakeMode
to set.
-
getBrakeMode
public SwerveDrivetrain.BrakeMode getBrakeMode()
Gets the currently selected swerve brake mode.- Returns:
- the currently selected
SwerveDrivetrain.BrakeMode
.
-
setMaxWheelAcceleration
public void setMaxWheelAcceleration(double maxAccel)
Sets the max acceleration for each wheel.- Parameters:
maxAccel
- the maximum acceleration.
-
modularizeEncoders
public void modularizeEncoders()
Resets the encoders to within [-4095, 4095] Call this method in `robotInit` to (almost) eliminate the possibility of accumulator rollover during one power cycle.
-
resetEncoder
public void resetEncoder(SwerveDrivetrain.WheelID wheelID)
Resets the position of the rotator encoder of the given wheel.This function should NEVER regularly be called. It should be called once per mechanical change, with all wheels facing forward.
- Parameters:
wheelID
- the wheel whose encoder should be reset.
-
resetPigeonYaw
public void resetPigeonYaw()
Resets the pigeon's yaw to consider the current orientation field-forward (zero degrees).
-
setPigeonYaw
public void setPigeonYaw(double angle)
Sets the pigeon's yaw to be a given value at the current position.- Parameters:
angle
- the value, in degrees, that the pigeon should have at the current position..
-
-