forked from BroncBotz3481/YAGSL
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathSwerveModule.java
538 lines (487 loc) · 17.1 KB
/
SwerveModule.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
package swervelib;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.math.SwerveMath;
import swervelib.motors.SwerveMotor;
import swervelib.parser.Cache;
import swervelib.parser.SwerveModuleConfiguration;
import swervelib.simulation.SwerveModuleSimulation;
import swervelib.telemetry.Alert;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
/**
* The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
*/
public class SwerveModule
{
/**
* Swerve module configuration options.
*/
public final SwerveModuleConfiguration configuration;
/**
* Absolute encoder position cache.
*/
public final Cache<Double> absolutePositionCache;
/**
* Drive motor position cache.
*/
public final Cache<Double> drivePositionCache;
/**
* Drive motor velocity cache.
*/
public final Cache<Double> driveVelocityCache;
/**
* Swerve Motors.
*/
private final SwerveMotor angleMotor, driveMotor;
/**
* Absolute encoder for swerve drive.
*/
private final SwerveAbsoluteEncoder absoluteEncoder;
/**
* An {@link Alert} for if pushing the Absolute Encoder offset to the encoder fails.
*/
private final Alert encoderOffsetWarning;
/**
* An {@link Alert} for if there is no Absolute Encoder on the module.
*/
private final Alert noEncoderWarning;
/**
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
public int moduleNumber;
/**
* Feedforward for drive motor during closed loop control.
*/
public SimpleMotorFeedforward feedforward;
/**
* Maximum speed of the drive motors in meters per second.
*/
public double maxSpeed;
/**
* Last swerve module state applied.
*/
private SwerveModuleState lastState;
/**
* Angle offset from the absolute encoder.
*/
private double angleOffset;
/**
* Simulated swerve module.
*/
private SwerveModuleSimulation simModule;
/**
* Encoder synchronization queued.
*/
private boolean synchronizeEncoderQueued = false;
/**
* Construct the swerve module and initialize the swerve module motors and absolute encoder.
*
* @param moduleNumber Module number for kinematics.
* @param moduleConfiguration Module constants containing CAN ID's and offsets.
* @param driveFeedforward Drive motor feedforward created by
* {@link SwerveMath#createDriveFeedforward(double, double, double)}.
*/
public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfiguration,
SimpleMotorFeedforward driveFeedforward)
{
// angle = 0;
// speed = 0;
// omega = 0;
// fakePos = 0;
this.moduleNumber = moduleNumber;
configuration = moduleConfiguration;
angleOffset = moduleConfiguration.angleOffset;
// Initialize Feedforward for drive motor.
feedforward = driveFeedforward;
// Create motors from configuration and reset them to defaults.
angleMotor = moduleConfiguration.angleMotor;
driveMotor = moduleConfiguration.driveMotor;
angleMotor.factoryDefaults();
driveMotor.factoryDefaults();
// Configure voltage comp, current limit, and ramp rate.
angleMotor.setVoltageCompensation(configuration.physicalCharacteristics.optimalVoltage);
driveMotor.setVoltageCompensation(configuration.physicalCharacteristics.optimalVoltage);
angleMotor.setCurrentLimit(configuration.physicalCharacteristics.angleMotorCurrentLimit);
driveMotor.setCurrentLimit(configuration.physicalCharacteristics.driveMotorCurrentLimit);
angleMotor.setLoopRampRate(configuration.physicalCharacteristics.angleMotorRampRate);
driveMotor.setLoopRampRate(configuration.physicalCharacteristics.driveMotorRampRate);
// Config angle encoders
absoluteEncoder = moduleConfiguration.absoluteEncoder;
if (absoluteEncoder != null)
{
absoluteEncoder.factoryDefault();
absoluteEncoder.configure(moduleConfiguration.absoluteEncoderInverted);
}
// Setup the cache for the absolute encoder position.
absolutePositionCache = new Cache<>(this::getRawAbsolutePosition, 15);
// Config angle motor/controller
angleMotor.configureIntegratedEncoder(moduleConfiguration.conversionFactors.angle);
angleMotor.configurePIDF(moduleConfiguration.anglePIDF);
angleMotor.configurePIDWrapping(0, 180);
angleMotor.setInverted(moduleConfiguration.angleMotorInverted);
angleMotor.setMotorBrake(false);
// Set the position AFTER settings the conversion factor.
if (absoluteEncoder != null)
{
angleMotor.setPosition(getAbsolutePosition());
}
// Config drive motor/controller
driveMotor.configureIntegratedEncoder(moduleConfiguration.conversionFactors.drive);
driveMotor.configurePIDF(moduleConfiguration.velocityPIDF);
driveMotor.setInverted(moduleConfiguration.driveMotorInverted);
driveMotor.setMotorBrake(true);
driveMotor.burnFlash();
angleMotor.burnFlash();
drivePositionCache = new Cache<>(driveMotor::getPosition, 15);
driveVelocityCache = new Cache<>(driveMotor::getVelocity, 15);
if (SwerveDriveTelemetry.isSimulation)
{
simModule = new SwerveModuleSimulation();
}
// Force a cache update on init.
driveVelocityCache.update();
drivePositionCache.update();
absolutePositionCache.update();
// Save the current state.
lastState = getState();
noEncoderWarning = new Alert("Motors",
"There is no Absolute Encoder on module #" +
moduleNumber,
Alert.AlertType.WARNING);
encoderOffsetWarning = new Alert("Motors",
"Pushing the Absolute Encoder offset to the encoder failed on module #" +
moduleNumber,
Alert.AlertType.WARNING);
}
/**
* Set the voltage compensation for the swerve module motor.
*
* @param optimalVoltage Nominal voltage for operation to output to.
*/
public void setAngleMotorVoltageCompensation(double optimalVoltage)
{
angleMotor.setVoltageCompensation(optimalVoltage);
}
/**
* Set the voltage compensation for the swerve module motor.
*
* @param optimalVoltage Nominal voltage for operation to output to.
*/
public void setDriveMotorVoltageCompensation(double optimalVoltage)
{
driveMotor.setVoltageCompensation(optimalVoltage);
}
/**
* Queue synchronization of the integrated angle encoder with the absolute encoder.
*/
public void queueSynchronizeEncoders()
{
if (absoluteEncoder != null)
{
synchronizeEncoderQueued = true;
}
}
/**
* Set the desired state of the swerve module. <br /><b>WARNING: If you are not using one of the functions from
* {@link SwerveDrive} you may screw up {@link SwerveDrive#kinematics}</b>
*
* @param desiredState Desired swerve module state.
* @param isOpenLoop Whether to use open loop (direct percent) or direct velocity control.
* @param force Disables optimizations that prevent movement in the angle motor and forces the desired state
* onto the swerve module.
*/
public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop, boolean force)
{
desiredState = SwerveModuleState.optimize(desiredState, Rotation2d.fromDegrees(getAbsolutePosition()));
// Cosine compensation.
double velocity = configuration.useCosineCompensator
? getCosineCompensatedVelocity(desiredState)
: desiredState.speedMetersPerSecond;
if (isOpenLoop)
{
double percentOutput = desiredState.speedMetersPerSecond / maxSpeed;
driveMotor.set(percentOutput);
} else
{
driveMotor.setReference(velocity, feedforward.calculate(velocity));
}
// If we are forcing the angle
if (!force)
{
// Prevents module rotation if speed is less than 1%
SwerveMath.antiJitter(desiredState, lastState, Math.min(maxSpeed, 4));
}
// Prevent module rotation if angle is the same as the previous angle.
// Synchronize encoders if queued and send in the current position as the value from the absolute encoder.
if (absoluteEncoder != null && synchronizeEncoderQueued)
{
double absoluteEncoderPosition = getAbsolutePosition();
angleMotor.setPosition(absoluteEncoderPosition);
angleMotor.setReference(desiredState.angle.getDegrees(), 0, absoluteEncoderPosition);
synchronizeEncoderQueued = false;
} else
{
angleMotor.setReference(desiredState.angle.getDegrees(), 0);
}
lastState = desiredState;
if (SwerveDriveTelemetry.isSimulation)
{
simModule.updateStateAndPosition(desiredState);
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.desiredStates[moduleNumber * 2] = desiredState.angle.getDegrees();
SwerveDriveTelemetry.desiredStates[(moduleNumber * 2) + 1] = velocity;
}
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
SmartDashboard.putNumber("Module[" + configuration.name + "] Speed Setpoint", desiredState.speedMetersPerSecond);
SmartDashboard.putNumber("Module[" + configuration.name + "] Angle Setpoint", desiredState.angle.getDegrees());
}
}
/**
* Get the cosine compensated velocity to set the swerve module to.
*
* @param desiredState Desired {@link SwerveModuleState} to use.
* @return Cosine compensated velocity in meters/second.
*/
private double getCosineCompensatedVelocity(SwerveModuleState desiredState)
{
double cosineScalar = 1.0;
// Taken from the CTRE SwerveModule class.
// https://api.ctr-electronics.com/phoenix6/release/java/src-html/com/ctre/phoenix6/mechanisms/swerve/SwerveModule.html#line.46
/* From FRC 900's whitepaper, we add a cosine compensator to the applied drive velocity */
/* To reduce the "skew" that occurs when changing direction */
double steerMotorError = desiredState.angle.getDegrees() - getAbsolutePosition();
/* If error is close to 0 rotations, we're already there, so apply full power */
/* If the error is close to 0.25 rotations, then we're 90 degrees, so movement doesn't help us at all */
cosineScalar = Math.cos(Units.degreesToRadians(steerMotorError));
/* Make sure we don't invert our drive, even though we shouldn't ever target over 90 degrees anyway */
if (cosineScalar < 0.0)
{
cosineScalar = 0.0;
}
return desiredState.speedMetersPerSecond * (cosineScalar);
}
/**
* Set the angle for the module.
*
* @param angle Angle in degrees.
*/
public void setAngle(double angle)
{
angleMotor.setReference(angle, 0);
lastState.angle = Rotation2d.fromDegrees(angle);
}
/**
* Get the Swerve Module state.
*
* @return Current SwerveModule state.
*/
public SwerveModuleState getState()
{
double velocity;
Rotation2d azimuth;
if (!SwerveDriveTelemetry.isSimulation)
{
velocity = driveVelocityCache.getValue();
azimuth = Rotation2d.fromDegrees(getAbsolutePosition());
} else
{
return simModule.getState();
}
return new SwerveModuleState(velocity, azimuth);
}
/**
* Get the position of the swerve module.
*
* @return {@link SwerveModulePosition} of the swerve module.
*/
public SwerveModulePosition getPosition()
{
double position;
Rotation2d azimuth;
if (!SwerveDriveTelemetry.isSimulation)
{
position = drivePositionCache.getValue();
azimuth = Rotation2d.fromDegrees(getAbsolutePosition());
} else
{
return simModule.getPosition();
}
return new SwerveModulePosition(position, azimuth);
}
/**
* Get the absolute position. Falls back to relative position on reading failure.
*
* @return Absolute encoder angle in degrees in the range [0, 360).
*/
public double getAbsolutePosition()
{
return absolutePositionCache.getValue();
}
/**
* Get the absolute position. Falls back to relative position on reading failure.
*
* @return Absolute encoder angle in degrees in the range [0, 360).
*/
public double getRawAbsolutePosition()
{
double angle;
if (absoluteEncoder != null)
{
angle = absoluteEncoder.getAbsolutePosition() - angleOffset;
if (absoluteEncoder.readingError)
{
angle = getRelativePosition();
}
} else
{
angle = getRelativePosition();
}
angle %= 360;
if (angle < 0.0)
{
angle += 360;
}
return angle;
}
/**
* Get the relative angle in degrees.
*
* @return Angle in degrees.
*/
public double getRelativePosition()
{
return angleMotor.getPosition();
}
/**
* Set the brake mode.
*
* @param brake Set the brake mode.
*/
public void setMotorBrake(boolean brake)
{
driveMotor.setMotorBrake(brake);
}
/**
* Set the conversion factor for the angle/azimuth motor controller.
*
* @param conversionFactor Angle motor conversion factor for PID, should be generated from
* {@link SwerveMath#calculateDegreesPerSteeringRotation(double, double)} or calculated.
*/
public void setAngleMotorConversionFactor(double conversionFactor)
{
angleMotor.configureIntegratedEncoder(conversionFactor);
}
/**
* Set the conversion factor for the drive motor controller.
*
* @param conversionFactor Drive motor conversion factor for PID, should be generated from
* {@link SwerveMath#calculateMetersPerRotation(double, double, double)} or calculated.
*/
public void setDriveMotorConversionFactor(double conversionFactor)
{
driveMotor.configureIntegratedEncoder(conversionFactor);
}
/**
* Get the angle {@link SwerveMotor} for the {@link SwerveModule}.
*
* @return {@link SwerveMotor} for the angle/steering motor of the module.
*/
public SwerveMotor getAngleMotor()
{
return angleMotor;
}
/**
* Get the drive {@link SwerveMotor} for the {@link SwerveModule}.
*
* @return {@link SwerveMotor} for the drive motor of the module.
*/
public SwerveMotor getDriveMotor()
{
return driveMotor;
}
/**
* Get the {@link SwerveAbsoluteEncoder} for the {@link SwerveModule}.
*
* @return {@link SwerveAbsoluteEncoder} for the swerve module.
*/
public SwerveAbsoluteEncoder getAbsoluteEncoder()
{
return absoluteEncoder;
}
/**
* Fetch the {@link SwerveModuleConfiguration} for the {@link SwerveModule} with the parsed configurations.
*
* @return {@link SwerveModuleConfiguration} for the {@link SwerveModule}.
*/
public SwerveModuleConfiguration getConfiguration()
{
return configuration;
}
/**
* Push absolute encoder offset in the memory of the encoder or controller. Also removes the internal angle offset.
*/
public void pushOffsetsToControllers()
{
if (absoluteEncoder != null)
{
if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
{
angleOffset = 0;
} else
{
encoderOffsetWarning.set(true);
}
} else
{
noEncoderWarning.set(true);
}
}
/**
* Restore internal offset in YAGSL and either sets absolute encoder offset to 0 or restores old value.
*/
public void restoreInternalOffset()
{
absoluteEncoder.setAbsoluteEncoderOffset(0);
angleOffset = configuration.angleOffset;
}
/**
* Get if the last Absolute Encoder had a read issue, such as it does not exist.
*
* @return If the last Absolute Encoder had a read issue, or absolute encoder does not exist.
*/
public boolean getAbsoluteEncoderReadIssue()
{
if (absoluteEncoder == null)
{
return true;
} else
{
return absoluteEncoder.readingError;
}
}
/**
* Update data sent to {@link SmartDashboard}.
*/
public void updateTelemetry()
{
if (absoluteEncoder != null)
{
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Absolute Encoder",
absoluteEncoder.getAbsolutePosition());
}
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Angle Encoder", angleMotor.getPosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Raw Drive Encoder", driveMotor.getPosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Adjusted Absolute Encoder", getAbsolutePosition());
SmartDashboard.putNumber("Module[" + configuration.name + "] Absolute Encoder Read Issue",
getAbsoluteEncoderReadIssue() ? 1 : 0);
}
}