Package frc.robot.subsystems.drivetrain
Class Drivetrain
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.subsystems.drivetrain.Drivetrain
Subsystem that controls the drivetrain.
-
Constructor Summary
ConstructorsConstructorDescriptionDrivetrain
(File directory) InitializeSwerveDrive
with the directory provided. -
Method Summary
Modifier and TypeMethodDescriptionCommand to center the modules of the SwerveDrive subsystem.void
drive
(Translation2d translation, double rotation, boolean fieldRelative) The primary method for controlling the drivebase.void
drive
(ChassisSpeeds velocity) Drive according to the chassis robot oriented velocity.driveAngularCommand
(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX) Command to drive the robot using translative values and heading as angular velocity.void
driveFieldOriented
(ChassisSpeeds velocity) Drive the robot given a chassis field oriented velocity.driveFieldOrientedCommand
(Supplier<ChassisSpeeds> velocity) Drive the robot given a chassis field oriented velocity.driveHeadingCommand
(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier headingX, DoubleSupplier headingY) Command to drive the robot using translative values and heading as a setpoint.driveToDistanceCommand
(double distanceInMeters, double speedInMetersPerSecond) Command that drives the swerve drive to a specific distance at a given speed.driveToNearestPoseCommand
(List<Pose2d> poseList) Drives to the nearest pose out of a list.driveToPoseCommand
(Supplier<Pose2d> pose) Use PathPlanner Path finding to go to a point on the field.driveWithSetpointGeneratorFieldRelativeCommand
(Supplier<ChassisSpeeds> fieldRelativeSpeeds) Drive with 254's Setpoint generator; port written by PathPlanner.Gets the current field-relative velocity (x, y and omega) of the robot.Gets the current yaw angle of the robot, as reported by the swerve pose estimator in the underlying drivebase.Get the swerve drive kinematics object.getPitch()
Gets the current pitch angle of the robot, as reported by the imu.getPose()
Gets the current pose (position and rotation) of the robot, as reported by odometry.Gets the current velocity (x, y and omega) of the robot.Get theSwerveController
in the swerve drive.Gets the swerve drive object.Get theSwerveDriveConfiguration
object.void
lock()
Lock the swerve drive to prevent it from moving.void
periodic()
void
postTrajectory
(Trajectory trajectory) Post the trajectory to the field.void
The method to reset what the heading control will turn to if no angle is inputed.void
Method to reset what the heading control will turn to if no angle is inputed.Command to reset what the heading control will turn to if no angle is inputed.The command to reset what the heading control will turn to if no angle is inputed.void
Inverted method to reset what the heading control will turn to if no angle is inputed.Inverted command to reset what the heading control will turn to if no angle is inputed.void
resetOdometry
(Pose2d initialHolonomicPose) Resets odometry to the given pose.void
setChassisSpeeds
(ChassisSpeeds chassisSpeeds) Set chassis speeds with closed-loop velocity control.void
setMotorBrake
(boolean brake) Sets the drive motors to brake/coast mode.void
Command to characterize the robot angle motors using SysId.Command to characterize the robot drive motors using SysId.void
zeroGyro()
Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.void
This will zero (calibrate) the robot to assume the current position is facing forwardMethods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, startEnd, startRun
-
Constructor Details
-
Drivetrain
InitializeSwerveDrive
with the directory provided.- Parameters:
directory
- Directory of swerve drive config files.
-
-
Method Details
-
periodic
public void periodic() -
simulationPeriodic
public void simulationPeriodic() -
getSwerveDrive
Gets the swerve drive object.- Returns:
SwerveDrive
-
getSwerveController
Get theSwerveController
in the swerve drive.- Returns:
SwerveController
from theSwerveDrive
.- See Also:
-
getSwerveDriveConfiguration
Get theSwerveDriveConfiguration
object.- Returns:
- The
SwerveDriveConfiguration
for the current drive. - See Also:
-
getKinematics
Get the swerve drive kinematics object.- Returns:
SwerveDriveKinematics
of the swerve drive.- See Also:
-
resetOdometry
Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this method. However, if either gyro angle or module position is reset, this must be called in order for odometry to keep working.- Parameters:
initialHolonomicPose
- The pose to set the odometry to- See Also:
-
getPose
Gets the current pose (position and rotation) of the robot, as reported by odometry.- Returns:
- The robot's pose
- See Also:
-
sysIdDriveMotorCommand
Command to characterize the robot drive motors using SysId.- Returns:
- SysId Drive Command
-
sysIdAngleMotorCommand
Command to characterize the robot angle motors using SysId.- Returns:
- SysId Angle Command
-
centerModulesCommand
Command to center the modules of the SwerveDrive subsystem.- Returns:
- Command to run
-
postTrajectory
Post the trajectory to the field.- Parameters:
trajectory
- The trajectory to post.- See Also:
-
zeroGyro
public void zeroGyro()Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.- See Also:
-
zeroGyroWithAlliance
public void zeroGyroWithAlliance()This will zero (calibrate) the robot to assume the current position is facing forwardIf red alliance rotate the robot 180 after the drviebase zero command
-
setMotorBrake
public void setMotorBrake(boolean brake) Sets the drive motors to brake/coast mode.- Parameters:
brake
- True to set motors to brake mode, false for coast.- See Also:
-
getHeading
Gets the current yaw angle of the robot, as reported by the swerve pose estimator in the underlying drivebase. Note, this is not the raw gyro reading, this may be corrected from calls to resetOdometry().- Returns:
- The yaw angle
-
getFieldVelocity
Gets the current field-relative velocity (x, y and omega) of the robot.- Returns:
- A ChassisSpeeds object of the current field-relative velocity
- See Also:
-
getRobotVelocity
Gets the current velocity (x, y and omega) of the robot.- Returns:
- A
ChassisSpeeds
object of the current velocity - See Also:
-
lock
public void lock()Lock the swerve drive to prevent it from moving.- See Also:
-
getPitch
Gets the current pitch angle of the robot, as reported by the imu.- Returns:
- The heading as a
Rotation2d
angle - See Also:
-
drive
The primary method for controlling the drivebase. Takes aTranslation2d
and a rotation rate, and calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used.- Parameters:
translation
-Translation2d
that is the commanded linear velocity of the robot, in meters per second. In robot-relative mode, positive x is torwards the bow (front) and positive y is torwards port (left). In field-relative mode, positive x is away from the alliance wall (field North) and positive y is torwards the left wall when looking through the driver station glass (field West).rotation
- Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot relativity.fieldRelative
- Drive mode. True for field-relative, false for robot-relative.- See Also:
-
resetLastAngleScalar
public void resetLastAngleScalar()The method to reset what the heading control will turn to if no angle is inputed. Used to prevent angle snapback.- Implementation Note:
- Running this on the Red alliance will cause the robot to flip 180 degrees. Call
resetLastAngleScalarByAlliance()
instead if that is not the desired behavior.
-
resetLastAngleScalarCommand
The command to reset what the heading control will turn to if no angle is inputed. Used to prevent angle snapback.- Returns:
Command
to run.- See Also:
-
resetLastAngleScalarInverted
public void resetLastAngleScalarInverted()Inverted method to reset what the heading control will turn to if no angle is inputed. Used to prevent angle snapback.- See Also:
- Implementation Note:
- Running this on the Blue alliance will cause the robot to flip 180 degrees. Call
resetLastAngleScalarByAlliance()
instead if that is not the desired behavior.
-
resetLastAngleScalarInvertedCommand
Inverted command to reset what the heading control will turn to if no angle is inputed. Used to prevent angle snapback.- Returns:
Command
to run.- See Also:
-
resetLastAngleScalarByAlliance
public void resetLastAngleScalarByAlliance()Method to reset what the heading control will turn to if no angle is inputed. Inverted based on alliance color. Used to prevent angle snapback. -
resetLastAngleScalarByAllianceCommand
Command to reset what the heading control will turn to if no angle is inputed. Inverted based on alliance color. Used to prevent angle snapback.- Returns:
Command
to run.- See Also:
-
driveToPoseCommand
Use PathPlanner Path finding to go to a point on the field.- Parameters:
pose
- TargetPose2d
to go to.- Returns:
- PathFinding command
- See Also:
-
driveToNearestPoseCommand
Drives to the nearest pose out of a list.- Parameters:
poseList
- List of poses to choose from.- Returns:
Command
to run.
-
driveWithSetpointGeneratorFieldRelativeCommand
public Command driveWithSetpointGeneratorFieldRelativeCommand(Supplier<ChassisSpeeds> fieldRelativeSpeeds) Drive with 254's Setpoint generator; port written by PathPlanner.- Parameters:
fieldRelativeSpeeds
- Field-RelativeChassisSpeeds
- Returns:
- Command to drive the robot using the setpoint generator.
- See Also:
-
driveWithSetpointGeneratorCommand(Supplier)
-
driveToDistanceCommand
Command that drives the swerve drive to a specific distance at a given speed.- Parameters:
distanceInMeters
- the distance to drive in metersspeedInMetersPerSecond
- the speed at which to drive in meters per second- Returns:
- Command to run
-
driveAngularCommand
public Command driveAngularCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX) Command to drive the robot using translative values and heading as angular velocity.- Parameters:
translationX
- Translation in the X direction. Cubed for smoother controls.translationY
- Translation in the Y direction. Cubed for smoother controls.angularRotationX
- Angular velocity of the robot to set. Cubed for smoother controls.- Returns:
- Command to run
- See Also:
-
driveHeadingCommand
public Command driveHeadingCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier headingX, DoubleSupplier headingY) Command to drive the robot using translative values and heading as a setpoint.- Parameters:
translationX
- Translation in the X direction. Cubed for smoother controls.translationY
- Translation in the Y direction. Cubed for smoother controls.headingX
- Heading X to calculate angle of the joystick.headingY
- Heading Y to calculate angle of the joystick.- Returns:
- Command to run
-
drive
Drive according to the chassis robot oriented velocity.- Parameters:
velocity
- Robot orientedChassisSpeeds
- See Also:
-
driveFieldOriented
Drive the robot given a chassis field oriented velocity.- Parameters:
velocity
- Velocity according to the field.- See Also:
-
driveFieldOrientedCommand
Drive the robot given a chassis field oriented velocity.- Parameters:
velocity
- Velocity according to the field.- Returns:
- Command to run
- See Also:
-
driveFieldOrientedAngularVelocityControllerCommand
driveFieldOrientedCommand(Supplier)
that usesDrivetrainControls.driveAngularVelocity(Drivetrain, CommandXboxController)
. CallsresetLastAngleScalar()
on end to prevent snapback.- Parameters:
controller
- Controller to use.- Returns:
- Command to run.
-
driveFieldOrientedDirectAngleControllerCommand
driveFieldOrientedCommand(Supplier)
that usesDrivetrainControls.driveDirectAngle(Drivetrain, CommandXboxController)
.- Parameters:
controller
- Controller to use.- Returns:
- Command to run.
-
driveFieldOrientedDirectAngleSimControllerCommand
driveFieldOrientedCommand(Supplier)
that usesDrivetrainControls.driveDirectAngleSim(Drivetrain, CommandXboxController)
.- Parameters:
controller
- Controller to use.- Returns:
- Command to run.
-
setChassisSpeeds
Set chassis speeds with closed-loop velocity control.- Parameters:
chassisSpeeds
- Chassis Speeds to set.- See Also:
-