-
Notifications
You must be signed in to change notification settings - Fork 37
/
SwerveDrive.java
1529 lines (1414 loc) · 61.5 KB
/
SwerveDrive.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
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
package swervelib;
import static edu.wpi.first.hal.FRCNetComm.tInstances.kRobotDriveSwerve_YAGSL;
import static edu.wpi.first.hal.FRCNetComm.tResourceType.kResourceType_RobotDrive;
import static edu.wpi.first.units.Units.Inches;
import static edu.wpi.first.units.Units.KilogramSquareMeters;
import static edu.wpi.first.units.Units.Kilograms;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Newtons;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Force;
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Notifier;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import java.util.Optional;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
import org.ironmaple.simulation.SimulatedArena;
import org.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation;
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig;
import swervelib.encoders.CANCoderSwerve;
import swervelib.imu.Pigeon2Swerve;
import swervelib.imu.SwerveIMU;
import swervelib.math.SwerveMath;
import swervelib.motors.TalonFXSwerve;
import swervelib.parser.Cache;
import swervelib.parser.SwerveControllerConfiguration;
import swervelib.parser.SwerveDriveConfiguration;
import swervelib.simulation.SwerveIMUSimulation;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
/**
* Swerve Drive class representing and controlling the swerve drive.
*/
public class SwerveDrive
{
/**
* Swerve Kinematics object.
*/
public final SwerveDriveKinematics kinematics;
/**
* Swerve drive configuration.
*/
public final SwerveDriveConfiguration swerveDriveConfiguration;
/**
* Swerve odometry.
*/
public final SwerveDrivePoseEstimator swerveDrivePoseEstimator;
/**
* IMU reading cache for robot readings.
*/
public final Cache<Rotation3d> imuReadingCache;
/**
* Swerve modules.
*/
private final SwerveModule[] swerveModules;
/**
* WPILib {@link Notifier} to keep odometry up to date.
*/
private final Notifier odometryThread;
/**
* Odometry lock to ensure thread safety.
*/
private final Lock odometryLock = new ReentrantLock();
/**
* Alert to recommend Tuner X if the configuration is compatible.
*/
private final Alert tunerXRecommendation = new Alert("Swerve Drive",
"Your Swerve Drive is compatible with Tuner X swerve generator, please consider using that instead of YAGSL. More information here!\n" +
"https://pro.docs.ctr-electronics.com/en/latest/docs/tuner/tuner-swerve/index.html",
AlertType.kWarning);
/**
* NT4 Publisher for the IMU reading.
*/
private final DoublePublisher rawIMUPublisher
= NetworkTableInstance.getDefault()
.getDoubleTopic(
"swerve/Raw IMU Yaw")
.publish();
/**
* NT4 Publisher for the IMU reading adjusted by offset and inversion.
*/
private final DoublePublisher adjustedIMUPublisher
= NetworkTableInstance.getDefault()
.getDoubleTopic(
"swerve/Adjusted IMU Yaw")
.publish();
/**
* Field object.
*/
public Field2d field = new Field2d();
/**
* Swerve controller for controlling heading of the robot.
*/
public SwerveController swerveController;
/**
* Correct chassis velocity in {@link SwerveDrive#drive(Translation2d, double, boolean, boolean)} using 254's
* correction.
*/
public boolean chassisVelocityCorrection = true;
/**
* Correct chassis velocity in {@link SwerveDrive#setChassisSpeeds(ChassisSpeeds chassisSpeeds)} (auto) using 254's
* correction during auto.
*/
public boolean autonomousChassisVelocityCorrection = false;
/**
* Correct for skew that scales with angular velocity in
* {@link SwerveDrive#drive(Translation2d, double, boolean, boolean)}
*/
public boolean angularVelocityCorrection = false;
/**
* Correct for skew that scales with angular velocity in
* {@link SwerveDrive#setChassisSpeeds(ChassisSpeeds chassisSpeeds)} during auto.
*/
public boolean autonomousAngularVelocityCorrection = false;
/**
* Angular Velocity Correction Coefficent (expected values between -0.15 and 0.15).
*/
public double angularVelocityCoefficient = 0;
/**
* Whether to correct heading when driving translationally. Set to true to enable.
*/
public boolean headingCorrection = false;
/**
* MapleSim SwerveDrive.
*/
private SwerveDriveSimulation mapleSimDrive;
/**
* Amount of seconds the duration of the timestep the speeds should be applied for.
*/
private double discretizationdtSeconds = 0.02;
/**
* Deadband for speeds in heading correction.
*/
private double HEADING_CORRECTION_DEADBAND = 0.01;
/**
* Swerve IMU device for sensing the heading of the robot.
*/
private SwerveIMU imu;
/**
* Simulation of the swerve drive.
*/
private SwerveIMUSimulation simIMU;
/**
* Counter to synchronize the modules relative encoder with absolute encoder when not moving.
*/
private int moduleSynchronizationCounter = 0;
/**
* The last heading set in radians.
*/
private double lastHeadingRadians = 0;
/**
* The absolute max speed that your robot can reach while translating in meters per second.
*/
private double attainableMaxTranslationalSpeedMetersPerSecond = 0;
/**
* The absolute max speed the robot can reach while rotating radians per second.
*/
private double attainableMaxRotationalVelocityRadiansPerSecond = 0;
/**
* Maximum speed of the robot in meters per second.
*/
private double maxChassisSpeedMPS;
/**
* Creates a new swerve drivebase subsystem. Robot is controlled via the {@link SwerveDrive#drive} method, or via the
* {@link SwerveDrive#setRawModuleStates} method. The {@link SwerveDrive#drive} method incorporates kinematics-- it
* takes a translation and rotation, as well as parameters for field-centric and closed-loop velocity control.
* {@link SwerveDrive#setRawModuleStates} takes a list of SwerveModuleStates and directly passes them to the modules.
* This subsystem also handles odometry.
*
* @param config The {@link SwerveDriveConfiguration} configuration to base the swerve drive off of.
* @param controllerConfig The {@link SwerveControllerConfiguration} to use when creating the
* {@link SwerveController}.
* @param maxSpeedMPS Maximum speed of the robot in meters per second, remember to use
* {@link Units#feetToMeters(double)} if you have feet per second!
* @param startingPose Starting {@link Pose2d} on the field.
*/
public SwerveDrive(
SwerveDriveConfiguration config, SwerveControllerConfiguration controllerConfig, double maxSpeedMPS,
Pose2d startingPose)
{
this.maxChassisSpeedMPS = maxSpeedMPS;
swerveDriveConfiguration = config;
swerveController = new SwerveController(controllerConfig);
// Create Kinematics from swerve module locations.
kinematics = new SwerveDriveKinematics(config.moduleLocationsMeters);
odometryThread = new Notifier(this::updateOdometry);
this.swerveModules = config.modules;
// Create an integrator for angle if the robot is being simulated to emulate an IMU
// If the robot is real, instantiate the IMU instead.
if (SwerveDriveTelemetry.isSimulation)
{
DriveTrainSimulationConfig simulationConfig = DriveTrainSimulationConfig.Default()
.withBumperSize(
Meters.of(config.getTracklength())
.plus(Inches.of(5)),
Meters.of(config.getTrackwidth())
.plus(Inches.of(5)))
.withRobotMass(Kilograms.of(config.physicalCharacteristics.robotMassKg))
.withCustomModuleTranslations(config.moduleLocationsMeters)
.withGyro(config.getGyroSim())
.withSwerveModule(() -> new SwerveModuleSimulation(
config.getDriveMotorSim(),
config.getAngleMotorSim(),
config.physicalCharacteristics.conversionFactor.drive.gearRatio,
config.physicalCharacteristics.conversionFactor.angle.gearRatio,
Volts.of(config.physicalCharacteristics.driveFrictionVoltage),
Volts.of(config.physicalCharacteristics.angleFrictionVoltage),
Inches.of(
config.physicalCharacteristics.conversionFactor.drive.diameter /
2),
KilogramSquareMeters.of(0.02),
config.physicalCharacteristics.wheelGripCoefficientOfFriction));
mapleSimDrive = new SwerveDriveSimulation(simulationConfig, startingPose);
// feed module simulation instances to modules
for (int i = 0; i < swerveModules.length; i++)
{
this.swerveModules[i].configureModuleSimulation(mapleSimDrive.getModules()[i], config.physicalCharacteristics);
}
// register the drivetrain simulation
SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive);
simIMU = new SwerveIMUSimulation(mapleSimDrive.getGyroSimulation());
imuReadingCache = new Cache<>(simIMU::getGyroRotation3d, 5L);
} else
{
imu = config.imu;
imu.factoryDefault();
imuReadingCache = new Cache<>(imu::getRotation3d, 5L);
}
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
swerveDrivePoseEstimator =
new SwerveDrivePoseEstimator(
kinematics,
getYaw(),
getModulePositions(),
startingPose); // x,y,heading in radians; Vision measurement std dev, higher=less weight
zeroGyro();
// Initialize Telemetry
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.ordinal())
{
SmartDashboard.putData("Field", field);
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
SwerveDriveTelemetry.maxSpeed = maxSpeedMPS;
SwerveDriveTelemetry.maxAngularVelocity = swerveController.config.maxAngularVelocity;
SwerveDriveTelemetry.moduleCount = swerveModules.length;
SwerveDriveTelemetry.sizeFrontBack = Units.metersToInches(SwerveMath.getSwerveModule(swerveModules, true,
false).moduleLocation.getX() +
SwerveMath.getSwerveModule(swerveModules,
false,
false).moduleLocation.getX());
SwerveDriveTelemetry.sizeLeftRight = Units.metersToInches(SwerveMath.getSwerveModule(swerveModules, false,
true).moduleLocation.getY() +
SwerveMath.getSwerveModule(swerveModules,
false,
false).moduleLocation.getY());
SwerveDriveTelemetry.wheelLocations = new double[SwerveDriveTelemetry.moduleCount * 2];
for (SwerveModule module : swerveModules)
{
SwerveDriveTelemetry.wheelLocations[module.moduleNumber * 2] = Units.metersToInches(
module.configuration.moduleLocation.getX());
SwerveDriveTelemetry.wheelLocations[(module.moduleNumber * 2) + 1] = Units.metersToInches(
module.configuration.moduleLocation.getY());
}
SwerveDriveTelemetry.measuredStates = new double[SwerveDriveTelemetry.moduleCount * 2];
SwerveDriveTelemetry.desiredStates = new double[SwerveDriveTelemetry.moduleCount * 2];
SwerveDriveTelemetry.desiredStatesObj = new SwerveModuleState[SwerveDriveTelemetry.moduleCount];
SwerveDriveTelemetry.measuredStatesObj = new SwerveModuleState[SwerveDriveTelemetry.moduleCount];
}
setOdometryPeriod(SwerveDriveTelemetry.isSimulation ? 0.004 : 0.02);
checkIfTunerXCompatible();
HAL.report(kResourceType_RobotDrive, kRobotDriveSwerve_YAGSL);
}
/**
* Update the cache validity period for the robot.
*
* @param imu IMU reading cache validity period in milliseconds.
* @param driveMotor Drive motor reading cache in milliseconds.
* @param absoluteEncoder Absolute encoder reading cache in milliseconds.
*/
public void updateCacheValidityPeriods(long imu, long driveMotor, long absoluteEncoder)
{
imuReadingCache.updateValidityPeriod(imu);
for (SwerveModule module : swerveModules)
{
module.drivePositionCache.updateValidityPeriod(driveMotor);
module.driveVelocityCache.updateValidityPeriod(driveMotor);
module.absolutePositionCache.updateValidityPeriod(absoluteEncoder);
}
}
/**
* Check all components to ensure that Tuner X Swerve Generator is recommended instead.
*/
private void checkIfTunerXCompatible()
{
boolean compatible = imu instanceof Pigeon2Swerve;
for (SwerveModule module : swerveModules)
{
compatible = compatible && module.getDriveMotor() instanceof TalonFXSwerve &&
module.getAngleMotor() instanceof TalonFXSwerve &&
module.getAbsoluteEncoder() instanceof CANCoderSwerve;
if (!compatible)
{
break;
}
}
if (compatible)
{
tunerXRecommendation.set(true);
}
}
/**
* Set the odometry update period in seconds.
*
* @param period period in seconds.
*/
public void setOdometryPeriod(double period)
{
odometryThread.stop();
SimulatedArena.overrideSimulationTimings(Seconds.of(period), 1);
odometryThread.startPeriodic(period);
}
/**
* Stop the odometry thread in favor of manually updating odometry.
*/
public void stopOdometryThread()
{
odometryThread.stop();
SimulatedArena.overrideSimulationTimings(Seconds.of(TimedRobot.kDefaultPeriod), 5);
}
/**
* 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)
{
for (SwerveModule module : swerveModules)
{
module.setAngleMotorConversionFactor(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)
{
for (SwerveModule module : swerveModules)
{
module.setDriveMotorConversionFactor(conversionFactor);
}
}
/**
* Fetch the latest odometry heading, should be trusted over {@link SwerveDrive#getYaw()}.
*
* @return {@link Rotation2d} of the robot heading.
*/
public Rotation2d getOdometryHeading()
{
return swerveDrivePoseEstimator.getEstimatedPosition().getRotation();
}
/**
* Set the heading correction capabilities of YAGSL.
*
* @param state {@link SwerveDrive#headingCorrection} state.
*/
public void setHeadingCorrection(boolean state)
{
setHeadingCorrection(state, HEADING_CORRECTION_DEADBAND);
}
/**
* Set the heading correction capabilities of YAGSL.
*
* @param state {@link SwerveDrive#headingCorrection} state.
* @param deadband {@link SwerveDrive#HEADING_CORRECTION_DEADBAND} deadband.
*/
public void setHeadingCorrection(boolean state, double deadband)
{
headingCorrection = state;
HEADING_CORRECTION_DEADBAND = deadband;
}
/**
* Tertiary method of controlling the drive base given velocity in both field oriented and robot oriented at the same
* time. The inputs are added together so this is not intneded to be used to give the driver both methods of control.
*
* @param fieldOrientedVelocity The field oriented velocties to use
* @param robotOrientedVelocity The robot oriented velocties to use
*/
public void driveFieldOrientedandRobotOriented(ChassisSpeeds fieldOrientedVelocity,
ChassisSpeeds robotOrientedVelocity)
{
fieldOrientedVelocity.toRobotRelativeSpeeds(getOdometryHeading());
drive(fieldOrientedVelocity.plus(robotOrientedVelocity));
}
/**
* Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
*
* @param velocity Velocity of the robot desired.
*/
public void driveFieldOriented(ChassisSpeeds velocity)
{
velocity.toRobotRelativeSpeeds(getOdometryHeading());
drive(velocity);
}
/**
* Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
*
* @param velocity Velocity of the robot desired.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void driveFieldOriented(ChassisSpeeds velocity, Translation2d centerOfRotationMeters)
{
velocity.toRobotRelativeSpeeds(getOdometryHeading());
drive(velocity, centerOfRotationMeters);
}
/**
* Secondary method for controlling the drivebase. Given a simple {@link ChassisSpeeds} set the swerve module states,
* to achieve the goal.
*
* @param velocity The desired robot-oriented {@link ChassisSpeeds} for the robot to achieve.
*/
public void drive(ChassisSpeeds velocity)
{
drive(velocity, false, new Translation2d());
}
/**
* Secondary method for controlling the drivebase. Given a simple {@link ChassisSpeeds} set the swerve module states,
* to achieve the goal.
*
* @param velocity The desired robot-oriented {@link ChassisSpeeds} for the robot to achieve.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void drive(ChassisSpeeds velocity, Translation2d centerOfRotationMeters)
{
drive(velocity, false, centerOfRotationMeters);
}
/**
* The primary method for controlling the drivebase. Takes a {@link Translation2d} 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.
*
* @param translation {@link 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).
* @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
* relativity.
* @param fieldRelative Drive mode. True for field-relative, false for robot-relative.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop,
Translation2d centerOfRotationMeters)
{
// Creates a robot-relative ChassisSpeeds object, converting from field-relative speeds if
// necessary.
ChassisSpeeds velocity = new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
if (fieldRelative)
{
velocity.toRobotRelativeSpeeds(getOdometryHeading());
}
drive(velocity, isOpenLoop, centerOfRotationMeters);
}
/**
* The primary method for controlling the drivebase. Takes a {@link Translation2d} 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.
*
* @param translation {@link 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).
* @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
* relativity.
* @param fieldRelative Drive mode. True for field-relative, false for robot-relative.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop)
{
// Creates a robot-relative ChassisSpeeds object, converting from field-relative speeds if
// necessary.
ChassisSpeeds velocity = new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
if (fieldRelative)
{
velocity.toRobotRelativeSpeeds(getOdometryHeading());
}
drive(velocity, isOpenLoop, new Translation2d());
}
/**
* The primary method for controlling the drivebase. Takes a {@link ChassisSpeeds}, and calculates and commands module
* states accordingly. Can use either open-loop or closed-loop velocity control for the wheel velocities. Applies
* heading correction if enabled and necessary.
*
* @param robotRelativeVelocity The chassis speeds to set the robot to achieve.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void drive(ChassisSpeeds robotRelativeVelocity, boolean isOpenLoop, Translation2d centerOfRotationMeters)
{
SwerveDriveTelemetry.startCtrlCycle();
robotRelativeVelocity = movementOptimizations(robotRelativeVelocity,
chassisVelocityCorrection,
angularVelocityCorrection);
// Heading Angular Velocity Deadband, might make a configuration option later.
// Originally made by Team 1466 Webb Robotics.
// Modified by Team 7525 Pioneers and BoiledBurntBagel of 6036
if (headingCorrection)
{
if (Math.abs(robotRelativeVelocity.omegaRadiansPerSecond) < HEADING_CORRECTION_DEADBAND
&& (Math.abs(robotRelativeVelocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(robotRelativeVelocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
{
robotRelativeVelocity.omegaRadiansPerSecond =
swerveController.headingCalculate(getOdometryHeading().getRadians(), lastHeadingRadians);
} else
{
lastHeadingRadians = getOdometryHeading().getRadians();
}
}
// Display commanded speed for testing
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeVelocity;
}
// Calculate required module states via kinematics
SwerveModuleState[] swerveModuleStates = kinematics.toSwerveModuleStates(robotRelativeVelocity,
centerOfRotationMeters);
setRawModuleStates(swerveModuleStates, robotRelativeVelocity, isOpenLoop);
}
/**
* Set the maximum speeds for desaturation.
*
* @param attainableMaxTranslationalSpeedMetersPerSecond The absolute max speed that your robot can reach while
* translating in meters per second.
* @param attainableMaxRotationalVelocityRadiansPerSecond The absolute max speed the robot can reach while rotating in
* radians per second.
*/
public void setMaximumSpeeds(
double attainableMaxTranslationalSpeedMetersPerSecond,
double attainableMaxRotationalVelocityRadiansPerSecond)
{
this.attainableMaxTranslationalSpeedMetersPerSecond = attainableMaxTranslationalSpeedMetersPerSecond;
this.attainableMaxRotationalVelocityRadiansPerSecond = attainableMaxRotationalVelocityRadiansPerSecond;
this.swerveController.config.maxAngularVelocity = attainableMaxRotationalVelocityRadiansPerSecond;
}
/**
* Get the maximum velocity from {@link SwerveDrive#attainableMaxTranslationalSpeedMetersPerSecond} or
* {@link SwerveDrive#maxChassisSpeedMPS} whichever is higher.
*
* @return Maximum speed in meters/second.
*/
public double getMaximumChassisVelocity()
{
return Math.max(this.attainableMaxTranslationalSpeedMetersPerSecond, maxChassisSpeedMPS);
}
/**
* Get the maximum drive velocity of a module as a {@link LinearVelocity}.
*
* @return {@link LinearVelocity} representing the maximum drive speed of a module.
*/
public LinearVelocity getMaximumModuleDriveVelocity()
{
return swerveModules[0].getMaxVelocity();
}
/**
* Get the maximum angular velocity of an azimuth/angle motor in the swerve module.
*
* @return {@link AngularVelocity} of the maximum azimuth/angle motor.
*/
public AngularVelocity getMaximumModuleAngleVelocity()
{
return swerveModules[0].getMaxAngularVelocity();
}
/**
* Get the maximum angular velocity, either {@link SwerveDrive#attainableMaxRotationalVelocityRadiansPerSecond} or
* {@link SwerveControllerConfiguration#maxAngularVelocity}.
*
* @return Maximum angular velocity in radians per second.
*/
public double getMaximumChassisAngularVelocity()
{
return Math.max(this.attainableMaxRotationalVelocityRadiansPerSecond, swerveController.config.maxAngularVelocity);
}
/**
* Set the module states (azimuth and velocity) directly.
*
* @param desiredStates A list of SwerveModuleStates to send to the modules.
* @param desiredChassisSpeed The desired chassis speeds to set the robot to achieve.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
*/
private void setRawModuleStates(SwerveModuleState[] desiredStates, ChassisSpeeds desiredChassisSpeed,
boolean isOpenLoop)
{
// Desaturates wheel speeds
double maxModuleSpeedMPS = getMaximumModuleDriveVelocity().in(MetersPerSecond);
if (attainableMaxTranslationalSpeedMetersPerSecond != 0 || attainableMaxRotationalVelocityRadiansPerSecond != 0)
{
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, desiredChassisSpeed,
maxModuleSpeedMPS,
attainableMaxTranslationalSpeedMetersPerSecond,
attainableMaxRotationalVelocityRadiansPerSecond);
} else
{
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, maxModuleSpeedMPS);
}
// Sets states
for (SwerveModule module : swerveModules)
{
module.setDesiredState(desiredStates[module.moduleNumber], isOpenLoop, false);
}
}
/**
* Set the module states (azimuth and velocity) directly. Used primarily for auto paths. Does not allow for usage of
* {@link SwerveDriveKinematics#desaturateWheelSpeeds(SwerveModuleState[] moduleStates, ChassisSpeeds
* desiredChassisSpeed, double attainableMaxModuleSpeedMetersPerSecond, double
* attainableMaxTranslationalSpeedMetersPerSecond, double attainableMaxRotationalVelocityRadiansPerSecond)}
*
* @param desiredStates A list of SwerveModuleStates to send to the modules.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
*/
public void setModuleStates(SwerveModuleState[] desiredStates, boolean isOpenLoop)
{
SwerveDriveTelemetry.startCtrlCycle();
double maxModuleSpeedMPS = getMaximumModuleDriveVelocity().in(MetersPerSecond);
desiredStates = kinematics.toSwerveModuleStates(kinematics.toChassisSpeeds(desiredStates));
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, maxModuleSpeedMPS);
// Sets states
for (SwerveModule module : swerveModules)
{
module.setDesiredState(desiredStates[module.moduleNumber], isOpenLoop, false);
}
}
/**
* Drive the robot using the {@link SwerveModuleState}, it is recommended to have
* {@link SwerveDrive#setCosineCompensator(boolean)} set to false for this.<br/>
* <p>
*
* @param robotRelativeVelocity Robot relative {@link ChassisSpeeds}
* @param states Corresponding {@link SwerveModuleState} to use (not checked against the
* {@param robotRelativeVelocity}).
* @param feedforwardForces Feedforward forces generated by set-point generator
*/
public void drive(ChassisSpeeds robotRelativeVelocity, SwerveModuleState[] states, Force[] feedforwardForces)
{
SwerveDriveTelemetry.startCtrlCycle();
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeVelocity;
}
for (SwerveModule module : swerveModules)
{
// from the module configuration, obtain necessary information to calculate feed-forward
// Warning: Will not work well if motor is not what we are expecting.
// Warning: Should replace module.getDriveMotor().simMotor with expected motor type first.
DCMotor driveMotorModel = module.configuration.driveMotor.getSimMotor();
double driveGearRatio = module.configuration.conversionFactors.drive.gearRatio;
double wheelRadiusMeters = Units.inchesToMeters(module.configuration.conversionFactors.drive.diameter) / 2;
// calculation:
double desiredGroundSpeedMPS = states[module.moduleNumber].speedMetersPerSecond;
double feedforwardVoltage = driveMotorModel.getVoltage(
// Since: (1) torque = force * momentOfForce; (2) torque (on wheel) = torque (on motor) * gearRatio
// torque (on motor) = force * wheelRadius / gearRatio
feedforwardForces[module.moduleNumber].in(Newtons) * wheelRadiusMeters / driveGearRatio,
// Since: (1) linear velocity = angularVelocity * wheelRadius; (2) wheelVelocity = motorVelocity / gearRatio
// motorAngularVelocity = linearVelocity / wheelRadius * gearRatio
desiredGroundSpeedMPS / wheelRadiusMeters * driveGearRatio
);
module.setDesiredState(
states[module.moduleNumber],
false,
feedforwardVoltage
);
}
}
/**
* Set chassis speeds with closed-loop velocity control.
*
* @param robotRelativeSpeeds Chassis speeds to set.
*/
public void setChassisSpeeds(ChassisSpeeds robotRelativeSpeeds)
{
SwerveDriveTelemetry.startCtrlCycle();
robotRelativeSpeeds = movementOptimizations(robotRelativeSpeeds,
autonomousChassisVelocityCorrection,
autonomousAngularVelocityCorrection);
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeSpeeds;
setRawModuleStates(kinematics.toSwerveModuleStates(robotRelativeSpeeds), robotRelativeSpeeds, false);
}
/**
* Gets the measured pose (position and rotation) of the robot, as reported by odometry.
*
* @return The robot's pose
*/
public Pose2d getPose()
{
odometryLock.lock();
Pose2d poseEstimation = swerveDrivePoseEstimator.getEstimatedPosition();
odometryLock.unlock();
return poseEstimation;
}
/**
* Gets the maple-sim drivetrain simulation instance This is used to add intake simulation / launch game pieces from
* the robot
*
* @return an optional maple-sim {@link SwerveDriveSimulation} object, or {@link Optional#empty()} when calling from a
* real robot
*/
public Optional<SwerveDriveSimulation> getMapleSimDrive()
{
if (SwerveDriveTelemetry.isSimulation)
{
return Optional.of(mapleSimDrive);
}
return Optional.empty();
}
/**
* Gets the actual pose of the drivetrain during simulation
*
* @return an {@link Optional} {@link Pose2d}, representing the drivetrain pose during simulation, or an empty
* optional when running on real robot
*/
public Optional<Pose2d> getSimulationDriveTrainPose()
{
odometryLock.lock();
Optional<Pose2d> simulationPose = getMapleSimDrive().map(AbstractDriveTrainSimulation::getSimulatedDriveTrainPose);
odometryLock.unlock();
return simulationPose;
}
/**
* Gets the measured field-relative robot velocity (x, y and omega)
*
* @return A ChassisSpeeds object of the current field-relative velocity
*/
public ChassisSpeeds getFieldVelocity()
{
// ChassisSpeeds has a method to convert from field-relative to robot-relative speeds,
// but not the reverse. However, because this transform is a simple rotation, negating the
// angle given as the robot angle reverses the direction of rotation, and the conversion is reversed.
ChassisSpeeds robotRelativeSpeeds = kinematics.toChassisSpeeds(getStates());
robotRelativeSpeeds.toFieldRelativeSpeeds(getOdometryHeading());//.unaryMinus());
return robotRelativeSpeeds;
}
/**
* Gets the current robot-relative velocity (x, y and omega) of the robot
*
* @return A ChassisSpeeds object of the current robot-relative velocity
*/
public ChassisSpeeds getRobotVelocity()
{
return kinematics.toChassisSpeeds(getStates());
}
/**
* 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.
*
* @param pose The pose to set the odometry to
*/
public void resetOdometry(Pose2d pose)
{
odometryLock.lock();
swerveDrivePoseEstimator.resetPosition(getYaw(), getModulePositions(), pose);
if (SwerveDriveTelemetry.isSimulation)
{
mapleSimDrive.setSimulationWorldPose(pose);
}
odometryLock.unlock();
ChassisSpeeds robotRelativeSpeeds = new ChassisSpeeds();
robotRelativeSpeeds.toFieldRelativeSpeeds(getYaw());
kinematics.toSwerveModuleStates(robotRelativeSpeeds);
}
/**
* Post the trajectory to the field
*
* @param trajectory the trajectory to post.
*/
public void postTrajectory(Trajectory trajectory)
{
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.ordinal())
{
field.getObject("Trajectory").setTrajectory(trajectory);
}
}
/**
* Gets the current module states (azimuth and velocity)
*
* @return A list of SwerveModuleStates containing the current module states
*/
public SwerveModuleState[] getStates()
{
SwerveModuleState[] states = new SwerveModuleState[swerveDriveConfiguration.moduleCount];
for (SwerveModule module : swerveModules)
{
states[module.moduleNumber] = module.getState();
}
return states;
}
/**
* Gets the current module positions (azimuth and wheel position (meters)).
*
* @return A list of SwerveModulePositions containg the current module positions
*/
public SwerveModulePosition[] getModulePositions()
{
SwerveModulePosition[] positions =
new SwerveModulePosition[swerveDriveConfiguration.moduleCount];
for (SwerveModule module : swerveModules)
{
positions[module.moduleNumber] = module.getPosition();
}
return positions;
}
/**
* Getter for the {@link SwerveIMU}.
*
* @return generated {@link SwerveIMU}
*/
public SwerveIMU getGyro()
{
return swerveDriveConfiguration.imu;
}
/**
* Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
* subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
*
* @param gyro expected gyroscope angle as {@link Rotation3d}.
*/
public void setGyro(Rotation3d gyro)
{
if (SwerveDriveTelemetry.isSimulation)
{
setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
} else
{
setGyroOffset(imu.getRawRotation3d().minus(gyro));
}
imuReadingCache.update();
}
/**
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
*/
public void zeroGyro()
{
// Resets the real gyro or the angle accumulator, depending on whether the robot is being
// simulated
if (SwerveDriveTelemetry.isSimulation)
{
simIMU.setAngle(0);
} else
{
setGyroOffset(imu.getRawRotation3d());
}
imuReadingCache.update();
swerveController.lastAngleScalar = 0;
lastHeadingRadians = 0;
resetOdometry(new Pose2d(getPose().getTranslation(), new Rotation2d()));
}
/**
* Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.
*
* @return The yaw as a {@link Rotation2d} angle
*/
public Rotation2d getYaw()
{
// Read the imu if the robot is real or the accumulator if the robot is simulated.
return Rotation2d.fromRadians(imuReadingCache.getValue().getZ());
}
/**
* Gets the current pitch angle of the robot, as reported by the imu.
*
* @return The heading as a {@link Rotation2d} angle
*/
public Rotation2d getPitch()
{
// Read the imu if the robot is real or the accumulator if the robot is simulated.
return Rotation2d.fromRadians(imuReadingCache.getValue().getY());
}
/**
* Gets the current roll angle of the robot, as reported by the imu.
*
* @return The heading as a {@link Rotation2d} angle