Package frc.robot.swerve
Class Swerve
java.lang.Object
com.ctre.phoenix6.swerve.SwerveDrivetrain<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>
frc.robot.swerve.Swerve
- All Implemented Interfaces:
edu.wpi.first.networktables.NTSendable,edu.wpi.first.util.sendable.Sendable,edu.wpi.first.wpilibj2.command.Subsystem,SpectrumSubsystem,AutoCloseable
public class Swerve
extends com.ctre.phoenix6.swerve.SwerveDrivetrain<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>
implements SpectrumSubsystem, edu.wpi.first.networktables.NTSendable
Class that extends the Phoenix SwerveDrivetrain class and implements subsystem so it can be used
in command-based projects easily.
-
Nested Class Summary
Nested classes/interfaces inherited from class com.ctre.phoenix6.swerve.SwerveDrivetrain
com.ctre.phoenix6.swerve.SwerveDrivetrain.DeviceConstructor<DeviceT extends Object>, com.ctre.phoenix6.swerve.SwerveDrivetrain.OdometryThread, com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveControlParameters, com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected edu.wpi.first.math.kinematics.SwerveModuleState[]Fields inherited from class com.ctre.phoenix6.swerve.SwerveDrivetrain
kNumConfigAttempts, m_drivetrainId, m_jni, m_telemetryJNI -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionbooleanatTagCenterGoal(double currentMeters) booleanatTagDistanceGoal(double currentArea) protected edu.wpi.first.wpilibj2.command.CommandbooleanfrontClosestToAngle(double angleDegrees) protected doubleprotected doubleprotected doubleedu.wpi.first.math.kinematics.ChassisSpeedsedu.wpi.first.math.geometry.Pose2dThe function `getRobotPose` returns the robot's pose after checking and updating it.doublegetRotationDifference(double angle1, double angle2) edu.wpi.first.math.kinematics.SwerveModuleState[]voidinitSendable(edu.wpi.first.networktables.NTSendableBuilder builder) The `initSendable` function sets up properties for a SmartDashboard type "SwerveDrive" with position and velocity double values.inXzone(double minXmeter, double maxXmeter) inXzoneAlliance(double minXmeter, double maxXmeter) This method is used to check if the robot is in the X zone of the field flips the values if Red AllianceinYzone(double minYmeter, double maxYmeter) inYzoneAlliance(double minYmeter, double maxYmeter) This method is used to check if the robot is in the Y zone of the field flips the values if Red Allianceprotected voidlog(com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState state) voidperiodic()This method is called periodically and is used to update the pilot's perspective.protected voidreorient(double angleDegrees) protected edu.wpi.first.wpilibj2.command.CommandreorientPilotAngle(double angleDegrees) voidvoidMethods inherited from class com.ctre.phoenix6.swerve.SwerveDrivetrain
addVisionMeasurement, addVisionMeasurement, close, configNeutralMode, getKinematics, getModule, getModuleLocations, getModules, getOdometryFrequency, getOdometryFrequencyMeasure, getOdometryThread, getOperatorForwardDirection, getPigeon2, getRotation3d, getState, getStateCopy, isOdometryValid, isOnCANFD, registerTelemetry, resetPose, resetRotation, resetTranslation, samplePoseAt, seedFieldCentric, setControl, setOperatorPerspectiveForward, setStateStdDevs, setVisionMeasurementStdDevs, tareEverything, updateSimStateMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.networktables.NTSendable
initSendableMethods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, getName, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
-
Field Details
-
setpoints
protected edu.wpi.first.math.kinematics.SwerveModuleState[] setpoints
-
-
Constructor Details
-
Swerve
Constructs a new Swerve drive subsystem.- Parameters:
config- The configuration object containing drivetrain constants and module configurations.
-
-
Method Details
-
log
protected void log(com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState state) -
periodic
public void periodic()This method is called periodically and is used to update the pilot's perspective. It ensures that the swerve drive system is aligned correctly based on the pilot's view.- Specified by:
periodicin interfaceedu.wpi.first.wpilibj2.command.Subsystem
-
setupStates
public void setupStates()- Specified by:
setupStatesin interfaceSpectrumSubsystem
-
setupDefaultCommand
public void setupDefaultCommand()- Specified by:
setupDefaultCommandin interfaceSpectrumSubsystem
-
initSendable
public void initSendable(edu.wpi.first.networktables.NTSendableBuilder builder) The `initSendable` function sets up properties for a SmartDashboard type "SwerveDrive" with position and velocity double values.- Specified by:
initSendablein interfaceedu.wpi.first.networktables.NTSendable- Parameters:
builder- The `builder` parameter is an instance of the `NTSendableBuilder` class
-
getRobotPose
public edu.wpi.first.math.geometry.Pose2d getRobotPose()The function `getRobotPose` returns the robot's pose after checking and updating it.- Returns:
- The `getRobotPose` method is returning the robot's current pose after calling the `seedCheckedPose` method with the current pose as an argument.
-
inXzone
-
inYzone
-
inXzoneAlliance
This method is used to check if the robot is in the X zone of the field flips the values if Red Alliance- Parameters:
minXmeter-maxXmeter-- Returns:
-
inYzoneAlliance
This method is used to check if the robot is in the Y zone of the field flips the values if Red Alliance- Parameters:
minYmeter-maxYmeter-- Returns:
-
getCurrentRobotChassisSpeeds
public edu.wpi.first.math.kinematics.ChassisSpeeds getCurrentRobotChassisSpeeds() -
reorient
protected void reorient(double angleDegrees) -
reorientPilotAngle
protected edu.wpi.first.wpilibj2.command.Command reorientPilotAngle(double angleDegrees) -
getClosestCardinal
protected double getClosestCardinal() -
getClosest45
protected double getClosest45() -
getClosestFieldAngle
protected double getClosestFieldAngle() -
cardinalReorient
protected edu.wpi.first.wpilibj2.command.Command cardinalReorient() -
frontClosestToAngle
public boolean frontClosestToAngle(double angleDegrees) -
getRotationDifference
public double getRotationDifference(double angle1, double angle2) -
atTagCenterGoal
public boolean atTagCenterGoal(double currentMeters) -
atTagDistanceGoal
public boolean atTagDistanceGoal(double currentArea) -
getConfig
-
getSetpoints
public edu.wpi.first.math.kinematics.SwerveModuleState[] getSetpoints()
-