11
11
import edu .wpi .first .math .kinematics .SwerveModulePosition ;
12
12
import edu .wpi .first .math .util .Units ;
13
13
import edu .wpi .first .wpilibj2 .command .button .CommandXboxController ;
14
+ import frc .robot .config .RobotConfig ;
15
+ import frc .robot .fms .FmsSubsystem ;
16
+ import frc .robot .util .ControllerHelpers ;
14
17
import frc .robot .util .scheduling .SubsystemPriority ;
15
18
import frc .robot .util .state_machines .StateMachine ;
16
19
import java .util .List ;
@@ -76,6 +79,12 @@ public class SwerveSubsystem extends StateMachine<SwerveState> {
76
79
private ChassisSpeeds robotRelativeSpeeds ;
77
80
private ChassisSpeeds fieldRelativeSpeeds ;
78
81
private boolean slowEnoughToFeed ;
82
+ private double goalSnapAngle = 0 ;
83
+
84
+ /** The latest requested teleop speeds. */
85
+ private ChassisSpeeds teleopSpeeds = new ChassisSpeeds ();
86
+
87
+ private ChassisSpeeds autoSpeeds = new ChassisSpeeds ();
79
88
80
89
public ChassisSpeeds getRobotRelativeSpeeds () {
81
90
return robotRelativeSpeeds ;
@@ -97,11 +106,65 @@ public List<SwerveModulePosition> getModulePositions() {
97
106
return modulePositions ;
98
107
}
99
108
109
+ public void setSnapToAngle (double angle ) {
110
+ goalSnapAngle = angle ;
111
+ }
112
+
100
113
public SwerveSubsystem (CommandXboxController driveController ) {
101
114
super (SubsystemPriority .SWERVE , SwerveState .TELEOP );
102
115
this .controller = driveController ;
103
116
}
104
117
118
+ public void setFieldRelativeAutoSpeeds (ChassisSpeeds speeds ) {
119
+ autoSpeeds = speeds ;
120
+ sendSwerveRequest ();
121
+ }
122
+
123
+ public void driveTeleop (double x , double y , double theta ) {
124
+ double leftY =
125
+ -1.0
126
+ * ControllerHelpers .getExponent (
127
+ ControllerHelpers .getDeadbanded (controller .getLeftY (), leftYDeadband ), 1.5 );
128
+ double leftX =
129
+ ControllerHelpers .getExponent (
130
+ ControllerHelpers .getDeadbanded (controller .getLeftX (), leftXDeadband ), 1.5 );
131
+ double rightX =
132
+ ControllerHelpers .getExponent (
133
+ ControllerHelpers .getDeadbanded (controller .getRightX (), rightXDeadband ), 2 );
134
+
135
+ if (RobotConfig .get ().swerve ().invertRotation ()) {
136
+ rightX *= -1.0 ;
137
+ }
138
+
139
+ if (RobotConfig .get ().swerve ().invertX ()) {
140
+ leftX *= -1.0 ;
141
+ }
142
+
143
+ if (RobotConfig .get ().swerve ().invertY ()) {
144
+ leftY *= -1.0 ;
145
+ }
146
+
147
+ if (FmsSubsystem .isRedAlliance ()) {
148
+ leftX *= -1.0 ;
149
+ leftY *= -1.0 ;
150
+ }
151
+
152
+ teleopSpeeds =
153
+ new ChassisSpeeds (
154
+ -1.0 * leftY * MaxSpeed ,
155
+ leftX * MaxSpeed ,
156
+ rightX * TELEOP_MAX_ANGULAR_RATE .getRadians ());
157
+
158
+ sendSwerveRequest ();
159
+ }
160
+
161
+ @ Override
162
+ public void robotPeriodic () {
163
+ super .robotPeriodic ();
164
+ // Once per loop send a swerve request to ensure data is fresh
165
+ sendSwerveRequest ();
166
+ }
167
+
105
168
@ Override
106
169
protected void collectInputs () {
107
170
modulePositions = calculateModulePositions ();
@@ -141,4 +204,37 @@ private boolean calculateMovingSlowEnoughForFloorShot(ChassisSpeeds speeds) {
141
204
142
205
return linearSpeed < MAX_FLOOR_SPEED_SHOOTING ;
143
206
}
207
+
208
+ private void sendSwerveRequest () {
209
+ switch (getState ()) {
210
+ case TELEOP ->
211
+ drivetrain .setControl (
212
+ drive
213
+ .withVelocityX (teleopSpeeds .vxMetersPerSecond )
214
+ .withVelocityY (teleopSpeeds .vyMetersPerSecond )
215
+ .withRotationalRate (teleopSpeeds .omegaRadiansPerSecond )
216
+ .withDriveRequestType (DriveRequestType .OpenLoopVoltage ));
217
+ case TELEOP_SNAPS ->
218
+ drivetrain .setControl (
219
+ driveToAngle
220
+ .withVelocityX (teleopSpeeds .vxMetersPerSecond )
221
+ .withVelocityY (teleopSpeeds .vyMetersPerSecond )
222
+ .withTargetDirection (Rotation2d .fromDegrees (goalSnapAngle ))
223
+ .withDriveRequestType (DriveRequestType .OpenLoopVoltage ));
224
+ case AUTO ->
225
+ drivetrain .setControl (
226
+ drive
227
+ .withVelocityX (autoSpeeds .vxMetersPerSecond )
228
+ .withVelocityY (autoSpeeds .vyMetersPerSecond )
229
+ .withRotationalRate (autoSpeeds .omegaRadiansPerSecond )
230
+ .withDriveRequestType (DriveRequestType .Velocity ));
231
+ case AUTO_SNAPS ->
232
+ drivetrain .setControl (
233
+ driveToAngle
234
+ .withVelocityX (autoSpeeds .vxMetersPerSecond )
235
+ .withVelocityY (autoSpeeds .vyMetersPerSecond )
236
+ .withTargetDirection (Rotation2d .fromDegrees (goalSnapAngle ))
237
+ .withDriveRequestType (DriveRequestType .Velocity ));
238
+ }
239
+ }
144
240
}
0 commit comments