Package frc.robot.subsystems.DriveTrain
Class DriveTrain
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.subsystems.DriveTrain.DriveTrain
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable
,edu.wpi.first.wpilibj2.command.Subsystem
- Direct Known Subclasses:
DriveTrainRealIO
public abstract class DriveTrain
extends edu.wpi.first.wpilibj2.command.SubsystemBase
-
Field Summary
Modifier and TypeFieldDescriptionprotected edu.wpi.first.networktables.StructPublisher<edu.wpi.first.math.geometry.Rotation2d>
State publisher for AdvantageScope.protected edu.wpi.first.networktables.StructArrayPublisher<edu.wpi.first.math.kinematics.SwerveModuleState>
State publisher for AdvantageScope.protected edu.wpi.first.networktables.StructArrayPublisher<edu.wpi.first.math.kinematics.SwerveModuleState>
State publisher for AdvantageScope.edu.wpi.first.math.kinematics.SwerveModuleState[]
The desired module states.The drive train's SwerveModule objects. -
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionedu.wpi.first.math.kinematics.ChassisSpeeds
discretize_chassis_speeds
(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Accounts for drift while simultaneously translating and rotating by discretizing.abstract edu.wpi.first.math.geometry.Rotation2d
Gets either the measured yaw from the AHRS or the calculated angle from the simulation.edu.wpi.first.math.kinematics.SwerveModulePosition[]
Returns the measured swerve module positions for odometry.edu.wpi.first.math.kinematics.SwerveModuleState[]
Returns the measured swerve module states for telemetry.protected abstract SwerveModule
initializeModule
(int drive_port, int steer_port, int sensor_port) Creates either a SwerveModuleRealIO or SwerveModuleSimIO object.void
periodic()
void
setModules
(edu.wpi.first.math.kinematics.SwerveModuleState[] module_states) Sends calculated inputs to swerve modules.void
setSwerveDrive
(double x_metersPerSecond, double y_metersPerSecond, double a_radiansPerSecond) Calculates and sends inputs to swerve modules given field-relative speeds.void
setSwerveDrive
(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds) Calculates and sends inputs to swerve modules given robot-relative speeds.void
Methods 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
-
Field Details
-
m_modules
The drive train's SwerveModule objects. -
m_module_states
public edu.wpi.first.math.kinematics.SwerveModuleState[] m_module_statesThe desired module states. -
adv_real_states_pub
protected edu.wpi.first.networktables.StructArrayPublisher<edu.wpi.first.math.kinematics.SwerveModuleState> adv_real_states_pubState publisher for AdvantageScope. -
adv_target_states_pub
protected edu.wpi.first.networktables.StructArrayPublisher<edu.wpi.first.math.kinematics.SwerveModuleState> adv_target_states_pubState publisher for AdvantageScope. -
adv_gyro_pub
protected edu.wpi.first.networktables.StructPublisher<edu.wpi.first.math.geometry.Rotation2d> adv_gyro_pubState publisher for AdvantageScope.
-
-
Constructor Details
-
DriveTrain
public DriveTrain()
-
-
Method Details
-
initializeModule
Creates either a SwerveModuleRealIO or SwerveModuleSimIO object.- Parameters:
drive_port
- port number of the drive motorsteer_port
- port number of the steer motorsensor_port
- port number of the module's CANcoder- Returns:
- The constructed SwerveModule object
-
setSwerveDrive
public void setSwerveDrive(double x_metersPerSecond, double y_metersPerSecond, double a_radiansPerSecond) Calculates and sends inputs to swerve modules given field-relative speeds. Calls setSwerveDrive(ChassisSpeeds chassis_speeds)- Parameters:
x_metersPerSecond
- X-axis speed in m/s. Forward is positive.y_metersPerSecond
- Y-axis speed in m/s. Right is positive.a_radiansPerSecond
- Angular speed in rad/s. CCW is positive.
-
setSwerveDrive
public void setSwerveDrive(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds) Calculates and sends inputs to swerve modules given robot-relative speeds.- Parameters:
chassis_speeds
- The desired robot-relative chassis speeds.
-
setModules
public void setModules(edu.wpi.first.math.kinematics.SwerveModuleState[] module_states) Sends calculated inputs to swerve modules.- Parameters:
module_states
- The desired module states.
-
discretize_chassis_speeds
public edu.wpi.first.math.kinematics.ChassisSpeeds discretize_chassis_speeds(edu.wpi.first.math.kinematics.ChassisSpeeds speeds) Accounts for drift while simultaneously translating and rotating by discretizing.- Parameters:
speeds
- Desired chassis speeds.- Returns:
- Adjusted chassis speeds.
-
getModulePositions
public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions()Returns the measured swerve module positions for odometry.- Returns:
- The measured swerve module positions.
-
getModuleStates
public edu.wpi.first.math.kinematics.SwerveModuleState[] getModuleStates()Returns the measured swerve module states for telemetry.- Returns:
- The measured swerve module states.
-
getGyroAngle
public abstract edu.wpi.first.math.geometry.Rotation2d getGyroAngle()Gets either the measured yaw from the AHRS or the calculated angle from the simulation. Forward is 0, CCW is positive.- Returns:
- The robot yaw.
-
periodic
public void periodic() -
simulationPeriodic
public void simulationPeriodic()
-