-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathDriveSubsystem.java
1333 lines (1186 loc) · 48.3 KB
/
DriveSubsystem.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
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.subsystems.drive;
import java.util.Optional;
import java.util.concurrent.ThreadLocalRandom;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;
import org.apache.commons.math3.analysis.polynomials.PolynomialSplineFunction;
import org.apache.commons.math3.geometry.euclidean.twod.Vector2D;
import org.lasarobotics.drive.AdvancedSwerveKinematics;
import org.lasarobotics.drive.AdvancedSwerveKinematics.ControlCentricity;
import org.lasarobotics.drive.MAXSwerveModule;
import org.lasarobotics.drive.ModuleLocation;
import org.lasarobotics.drive.RotatePIDController;
import org.lasarobotics.drive.SwervePoseEstimatorService;
import org.lasarobotics.drive.ThrottleMap;
import org.lasarobotics.hardware.kauailabs.NavX2;
import org.lasarobotics.hardware.revrobotics.Spark.MotorKind;
import org.lasarobotics.led.LEDStrip.Pattern;
import org.lasarobotics.led.LEDSubsystem;
import org.lasarobotics.utils.CommonTriggers;
import org.lasarobotics.utils.GlobalConstants;
import org.lasarobotics.utils.PIDConstants;
import org.lasarobotics.vision.AprilTagCamera;
import org.littletonrobotics.junction.Logger;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.path.PathConstraints;
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PathPlannerLogging;
import com.pathplanner.lib.util.ReplanningConfig;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
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.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Current;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.Mass;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.Units;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants;
import frc.robot.subsystems.vision.VisionSubsystem;
public class DriveSubsystem extends SubsystemBase implements AutoCloseable {
public static class Hardware {
NavX2 navx;
MAXSwerveModule lFrontModule;
MAXSwerveModule rFrontModule;
MAXSwerveModule lRearModule;
MAXSwerveModule rRearModule;
AprilTagCamera frontCamera;
AprilTagCamera rearCamera;
public Hardware(NavX2 navx,
MAXSwerveModule lFrontModule,
MAXSwerveModule rFrontModule,
MAXSwerveModule lRearModule,
MAXSwerveModule rRearModule,
AprilTagCamera frontCamera,
AprilTagCamera rearCamera) {
this.navx = navx;
this.lFrontModule = lFrontModule;
this.rFrontModule = rFrontModule;
this.lRearModule = lRearModule;
this.rRearModule = rRearModule;
this.frontCamera = frontCamera;
this.rearCamera = rearCamera;
}
}
// Drive specs
public static final Measure<Distance> DRIVE_WHEELBASE = Units.Meters.of(0.5588);
public static final Measure<Distance> DRIVE_TRACK_WIDTH = Units.Meters.of(0.5588);
public static final Measure<Mass> MASS = Units.Pounds.of(110.0);
public static final Measure<Time> AUTO_LOCK_TIME = Units.Seconds.of(3.0);
public static final Measure<Current> DRIVE_CURRENT_LIMIT = Units.Amps.of(60.0);
public static final Measure<Velocity<Angle>> NAVX2_YAW_DRIFT_RATE = Units.DegreesPerSecond.of(0.5 / 60);
public static final Measure<Velocity<Angle>> DRIVE_ROTATE_VELOCITY = Units.RadiansPerSecond.of(12 * Math.PI);
public static final Measure<Velocity<Angle>> AIM_VELOCITY_THRESHOLD = Units.DegreesPerSecond.of(5.0);
public static final Measure<Velocity<Angle>> VISION_ANGULAR_VELOCITY_THRESHOLD = Units.DegreesPerSecond.of(720.0);
public static final Measure<Velocity<Velocity<Angle>>> DRIVE_ROTATE_ACCELERATION = Units.RadiansPerSecond.of(4 * Math.PI).per(Units.Second);
public final Measure<Velocity<Distance>> DRIVE_MAX_LINEAR_SPEED;
public final Measure<Velocity<Velocity<Distance>>> DRIVE_AUTO_ACCELERATION;
// Other settings
private static final double TIP_THRESHOLD = 35.0;
private static final double TOLERANCE = 1.5;
private static final double BALANCED_THRESHOLD = 10.0;
private static final double AIM_VELOCITY_COMPENSATION_FUDGE_FACTOR = 0.5;
private static final Matrix<N3, N1> ODOMETRY_STDDEV = VecBuilder.fill(0.03, 0.03, Math.toRadians(1.0));
private static final Matrix<N3, N1> VISION_STDDEV = VecBuilder.fill(1.0, 1.0, Math.toRadians(3.0));
private static final PIDConstants AUTO_AIM_PID = new PIDConstants(10.0, 0.0, 0.5, 0.0, 0.0, GlobalConstants.ROBOT_LOOP_PERIOD);
private static final TrapezoidProfile.Constraints AIM_PID_CONSTRAINT = new TrapezoidProfile.Constraints(2160.0, 4320.0);
private static final Measure<Angle> BLUE_AMP_DIRECTION = Units.Radians.of(-Math.PI / 2);
private static final Measure<Angle> BLUE_SOURCE_DIRECTION = Units.Radians.of(-1.060 + Math.PI);
private static final Measure<Angle> RED_AMP_DIRECTION = Units.Radians.of(-Math.PI / 2);
private static final Measure<Angle> RED_SOURCE_DIRECTION = Units.Radians.of(-2.106 + Math.PI);
private static Measure<Angle> m_selectedAmpDirection = BLUE_AMP_DIRECTION;
private static Measure<Angle> m_selectedSourceDirection = BLUE_SOURCE_DIRECTION;
// Log
private static final String POSE_LOG_ENTRY = "/Pose";
private static final String ACTUAL_SWERVE_STATE_LOG_ENTRY = "/ActualSwerveState";
private static final String DESIRED_SWERVE_STATE_LOG_ENTRY = "/DesiredSwerveState";
private static final String IS_AIMED_LOG_ENTRY = "/IsAimed";
private final Command SET_ALLIANCE_COMMAND = Commands.runOnce(() -> {
// Try to get alliance
var alliance = DriverStation.getAlliance();
if (alliance.isEmpty()) return;
// Set alliance if available
setAlliance(alliance.get());
}).andThen(Commands.waitSeconds(1)).ignoringDisable(true).repeatedly();
public final Command ANTI_TIP_COMMAND = new FunctionalCommand(
() -> LEDSubsystem.getInstance().startOverride(Pattern.RED_STROBE),
() -> antiTip(),
(interrupted) -> {
resetRotatePID();
stop();
lock();
LEDSubsystem.getInstance().endOverride();
},
this::isBalanced,
this
);
private ThrottleMap m_throttleMap;
private RotatePIDController m_rotatePIDController;
private ProfiledPIDController m_autoAimPIDControllerFront;
private ProfiledPIDController m_autoAimPIDControllerBack;
private SwerveDriveKinematics m_kinematics;
private SwervePoseEstimatorService m_swervePoseEstimatorService;
private AdvancedSwerveKinematics m_advancedKinematics;
private HolonomicPathFollowerConfig m_pathFollowerConfig;
private NavX2 m_navx;
private MAXSwerveModule m_lFrontModule;
private MAXSwerveModule m_rFrontModule;
private MAXSwerveModule m_lRearModule;
private MAXSwerveModule m_rRearModule;
private ControlCentricity m_controlCentricity;
private ChassisSpeeds m_desiredChassisSpeeds;
private Rotation2d m_allianceCorrection;
private Pose2d m_previousPose;
private Rotation2d m_currentHeading;
private PurplePathClient m_purplePathClient;
private Field2d m_field;
private Alliance m_currentAlliance;
private boolean m_isTractionControlEnabled = true;
private boolean m_autoAimFront = false;
private boolean m_autoAimBack = false;
/**
* Create an instance of DriveSubsystem
* <p>
* NOTE: ONLY ONE INSTANCE SHOULD EXIST AT ANY TIME!
* <p>
* @param drivetrainHardware Hardware devices required by drivetrain
* @param pidf PID constants
* @param controlCentricity Control centricity
* @param throttleInputCurve Spline function characterising throttle input
* @param turnInputCurve Spline function characterising turn input
* @param turnScalar Scalar for turn input (degrees)
* @param deadband Deadband for controller input [+0.001, +0.2]
* @param lookAhead Rotate PID lookahead, in number of loops
*/
public DriveSubsystem(Hardware drivetrainHardware, PIDConstants pidf, ControlCentricity controlCentricity,
PolynomialSplineFunction throttleInputCurve, PolynomialSplineFunction turnInputCurve,
double turnScalar, double deadband, double lookAhead) {
setSubsystem(getClass().getSimpleName());
DRIVE_MAX_LINEAR_SPEED = drivetrainHardware.lFrontModule.getMaxLinearSpeed();
DRIVE_AUTO_ACCELERATION = DRIVE_MAX_LINEAR_SPEED.per(Units.Second).minus(Units.MetersPerSecondPerSecond.of(1.0));
this.m_navx = drivetrainHardware.navx;
this.m_lFrontModule = drivetrainHardware.lFrontModule;
this.m_rFrontModule = drivetrainHardware.rFrontModule;
this.m_lRearModule = drivetrainHardware.lRearModule;
this.m_rRearModule = drivetrainHardware.rRearModule;
this.m_controlCentricity = controlCentricity;
this.m_throttleMap = new ThrottleMap(throttleInputCurve, DRIVE_MAX_LINEAR_SPEED, deadband);
this.m_rotatePIDController = new RotatePIDController(turnInputCurve, pidf, turnScalar, deadband, lookAhead);
this.m_pathFollowerConfig = new HolonomicPathFollowerConfig(
new com.pathplanner.lib.util.PIDConstants(5.0, 0.0, 0.2),
new com.pathplanner.lib.util.PIDConstants(5.0, 0.0, 0.1),
DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond),
m_lFrontModule.getModuleCoordinate().getNorm(),
new ReplanningConfig(),
GlobalConstants.ROBOT_LOOP_PERIOD
);
this.m_currentAlliance = Alliance.Blue;
this.m_allianceCorrection = GlobalConstants.ROTATION_ZERO;
// Calibrate and reset navX
while (m_navx.isCalibrating()) stop();
m_navx.reset();
// Setup rotate PID
m_rotatePIDController.setTolerance(TOLERANCE);
m_rotatePIDController.setSetpoint(getAngle().in(Units.Degrees));
// Define drivetrain kinematics
m_kinematics = new SwerveDriveKinematics(m_lFrontModule.getModuleCoordinate(),
m_rFrontModule.getModuleCoordinate(),
m_lRearModule.getModuleCoordinate(),
m_rRearModule.getModuleCoordinate());
// Define advanced drivetrain kinematics
m_advancedKinematics = new AdvancedSwerveKinematics(m_lFrontModule.getModuleCoordinate(),
m_rFrontModule.getModuleCoordinate(),
m_lRearModule.getModuleCoordinate(),
m_rRearModule.getModuleCoordinate());
// Initialise pose estimator
m_swervePoseEstimatorService = new SwervePoseEstimatorService(
ODOMETRY_STDDEV,
m_navx,
m_lFrontModule,
m_rFrontModule,
m_lRearModule,
m_rRearModule
);
m_swervePoseEstimatorService.addAprilTagCamera(drivetrainHardware.frontCamera, drivetrainHardware.rearCamera);
m_swervePoseEstimatorService.start();
// Initialise chassis speeds
m_desiredChassisSpeeds = new ChassisSpeeds();
// Setup anti-tip command
new Trigger(this::isTipping).whileTrue(ANTI_TIP_COMMAND);
// Setup auto-aim PID controller
m_autoAimPIDControllerFront = new ProfiledPIDController(AUTO_AIM_PID.kP, 0.0, AUTO_AIM_PID.kD, AIM_PID_CONSTRAINT, AUTO_AIM_PID.period);
m_autoAimPIDControllerFront.enableContinuousInput(-180.0, +180.0);
m_autoAimPIDControllerFront.setTolerance(TOLERANCE);
m_autoAimPIDControllerFront.setIZone(AUTO_AIM_PID.kIZone);
m_autoAimPIDControllerBack = new ProfiledPIDController(AUTO_AIM_PID.kP, 0.0, AUTO_AIM_PID.kD, AIM_PID_CONSTRAINT, AUTO_AIM_PID.period);
m_autoAimPIDControllerBack.enableContinuousInput(-180.0, +180.0);
m_autoAimPIDControllerBack.setTolerance(TOLERANCE);
m_autoAimPIDControllerBack.setIZone(AUTO_AIM_PID.kIZone);
// Initialise other variables
m_previousPose = new Pose2d();
m_currentHeading = new Rotation2d();
// Initalise PurplePathClient
m_purplePathClient = new PurplePathClient(this);
// Set alliance triggers
CommonTriggers.isDSAttached().onTrue(SET_ALLIANCE_COMMAND);
RobotModeTriggers.disabled().whileTrue(SET_ALLIANCE_COMMAND);
// Initialise field
m_field = new Field2d();
SmartDashboard.putData(m_field);
// Setup path logging callback
PathPlannerLogging.setLogActivePathCallback(poses -> {
if (poses.size() < 1) return;
var trajectory = TrajectoryGenerator.generateTrajectory(
poses,
new TrajectoryConfig(DRIVE_MAX_LINEAR_SPEED, DRIVE_AUTO_ACCELERATION)
);
m_field.getObject("currentPath").setTrajectory(trajectory);
});
}
/**
* Initialize hardware devices for drive subsystem
* @return Hardware object containing all necessary devices for this subsystem
*/
public static Hardware initializeHardware() {
NavX2 navx = new NavX2(Constants.DriveHardware.NAVX_ID, GlobalConstants.ROBOT_LOOP_HZ * 2);
MAXSwerveModule lFrontModule = new MAXSwerveModule(
MAXSwerveModule.initializeHardware(
Constants.DriveHardware.LEFT_FRONT_DRIVE_MOTOR_ID,
Constants.DriveHardware.LEFT_FRONT_ROTATE_MOTOR_ID,
MotorKind.NEO_VORTEX
),
ModuleLocation.LeftFront,
Constants.Drive.GEAR_RATIO,
Constants.Drive.DRIVE_WHEEL,
Constants.Drive.DRIVE_SLIP_RATIO,
MASS,
DRIVE_WHEELBASE,
DRIVE_TRACK_WIDTH,
AUTO_LOCK_TIME,
DRIVE_CURRENT_LIMIT
);
MAXSwerveModule rFrontModule = new MAXSwerveModule(
MAXSwerveModule.initializeHardware(
Constants.DriveHardware.RIGHT_FRONT_DRIVE_MOTOR_ID,
Constants.DriveHardware.RIGHT_FRONT_ROTATE_MOTOR_ID,
MotorKind.NEO_VORTEX
),
ModuleLocation.RightFront,
Constants.Drive.GEAR_RATIO,
Constants.Drive.DRIVE_WHEEL,
Constants.Drive.DRIVE_SLIP_RATIO,
MASS,
DRIVE_WHEELBASE,
DRIVE_TRACK_WIDTH,
AUTO_LOCK_TIME,
DRIVE_CURRENT_LIMIT
);
MAXSwerveModule lRearModule = new MAXSwerveModule(
MAXSwerveModule.initializeHardware(
Constants.DriveHardware.LEFT_REAR_DRIVE_MOTOR_ID,
Constants.DriveHardware.LEFT_REAR_ROTATE_MOTOR_ID,
MotorKind.NEO_VORTEX
),
ModuleLocation.LeftRear,
Constants.Drive.GEAR_RATIO,
Constants.Drive.DRIVE_WHEEL,
Constants.Drive.DRIVE_SLIP_RATIO,
MASS,
DRIVE_WHEELBASE,
DRIVE_TRACK_WIDTH,
AUTO_LOCK_TIME,
DRIVE_CURRENT_LIMIT
);
MAXSwerveModule rRearModule = new MAXSwerveModule(
MAXSwerveModule.initializeHardware(
Constants.DriveHardware.RIGHT_REAR_DRIVE_MOTOR_ID,
Constants.DriveHardware.RIGHT_REAR_ROTATE_MOTOR_ID,
MotorKind.NEO_VORTEX
),
ModuleLocation.RightRear,
Constants.Drive.GEAR_RATIO,
Constants.Drive.DRIVE_WHEEL,
Constants.Drive.DRIVE_SLIP_RATIO,
MASS,
DRIVE_WHEELBASE,
DRIVE_TRACK_WIDTH,
AUTO_LOCK_TIME,
DRIVE_CURRENT_LIMIT
);
AprilTagCamera frontCamera = new AprilTagCamera(
Constants.VisionHardware.CAMERA_A_NAME,
Constants.VisionHardware.CAMERA_A_LOCATION,
Constants.VisionHardware.CAMERA_A_RESOLUTION,
Constants.VisionHardware.CAMERA_A_FOV,
AprilTagFields.k2024Crescendo.loadAprilTagLayoutField()
);
AprilTagCamera rearCamera = new AprilTagCamera(
Constants.VisionHardware.CAMERA_B_NAME,
Constants.VisionHardware.CAMERA_B_LOCATION,
Constants.VisionHardware.CAMERA_B_RESOLUTION,
Constants.VisionHardware.CAMERA_B_FOV,
AprilTagFields.k2024Crescendo.loadAprilTagLayoutField()
);
Hardware drivetrainHardware = new Hardware(navx, lFrontModule, rFrontModule, lRearModule, rRearModule, frontCamera, rearCamera);
return drivetrainHardware;
}
/**
* Set swerve modules
* @param moduleStates Array of calculated module states
*/
private void setSwerveModules(SwerveModuleState[] moduleStates) {
m_lFrontModule.set(moduleStates);
m_rFrontModule.set(moduleStates);
m_lRearModule.set(moduleStates);
m_rRearModule.set(moduleStates);
Logger.recordOutput(getName() + DESIRED_SWERVE_STATE_LOG_ENTRY, moduleStates);
}
/**
* Set swerve modules, automatically applying traction control
* @param moduleStates Array of calculated module states
* @param inertialVelocity Current inertial velocity
* @param rotateRate Current robot rotate rate
*/
private void setSwerveModules(SwerveModuleState[] moduleStates, Measure<Velocity<Distance>> inertialVelocity, Measure<Velocity<Angle>> rotateRate) {
m_lFrontModule.set(moduleStates, inertialVelocity, rotateRate);
m_rFrontModule.set(moduleStates, inertialVelocity, rotateRate);
m_lRearModule.set(moduleStates, inertialVelocity, rotateRate);
m_rRearModule.set(moduleStates, inertialVelocity, rotateRate);
Logger.recordOutput(getName() + DESIRED_SWERVE_STATE_LOG_ENTRY, moduleStates);
}
/**
* Drive robot and apply traction control
* @param xRequest Desired X (forward) velocity
* @param yRequest Desired Y (sideways) velocity
* @param rotateRequest Desired rotate rate
* @param inertialVelocity Current robot inertial velocity
*/
private void drive(ControlCentricity controlCentricity,
Measure<Velocity<Distance>> xRequest,
Measure<Velocity<Distance>> yRequest,
Measure<Velocity<Angle>> rotateRequest,
Measure<Velocity<Distance>> inertialVelocity,
Measure<Velocity<Angle>> rotateRate) {
// Get requested chassis speeds, correcting for second order kinematics
m_desiredChassisSpeeds = AdvancedSwerveKinematics.correctForDynamics(
new ChassisSpeeds(xRequest, yRequest, rotateRequest)
);
// Convert speeds to module states, correcting for 2nd order kinematics
SwerveModuleState[] moduleStates = m_advancedKinematics.toSwerveModuleStates(
m_desiredChassisSpeeds,
getPose().getRotation().plus(m_allianceCorrection),
controlCentricity
);
// Desaturate drive speeds
SwerveDriveKinematics.desaturateWheelSpeeds(moduleStates, DRIVE_MAX_LINEAR_SPEED);
// Set modules to calculated states, WITH traction control
setSwerveModules(moduleStates, inertialVelocity, rotateRate);
}
/**
* Drive robot without traction control
* @param xRequest Desired X (forward) velocity
* @param yRequest Desired Y (sideways) velocity
* @param rotateRequest Desired rotate rate
*/
private void drive(ControlCentricity controlCentricity,
Measure<Velocity<Distance>> xRequest,
Measure<Velocity<Distance>> yRequest,
Measure<Velocity<Angle>> rotateRequest) {
// Get requested chassis speeds, correcting for second order kinematics
m_desiredChassisSpeeds = AdvancedSwerveKinematics.correctForDynamics(
new ChassisSpeeds(xRequest, yRequest, rotateRequest)
);
// Convert speeds to module states, correcting for 2nd order kinematics
SwerveModuleState[] moduleStates = m_advancedKinematics.toSwerveModuleStates(
m_desiredChassisSpeeds,
getPose().getRotation().plus(m_allianceCorrection),
controlCentricity
);
// Desaturate drive speeds
SwerveDriveKinematics.desaturateWheelSpeeds(moduleStates, DRIVE_MAX_LINEAR_SPEED);
// Set modules to calculated states, WITHOUT traction control
setSwerveModules(moduleStates);
}
/**
* Get current module states
* @return Array of swerve module states
*/
private SwerveModuleState[] getModuleStates() {
return new SwerveModuleState[] {
m_lFrontModule.getState(),
m_rFrontModule.getState(),
m_lRearModule.getState(),
m_rRearModule.getState()
};
}
/**
* Get current module positions
* @return Array of swerve module positions
*/
private SwerveModulePosition[] getModulePositions() {
return new SwerveModulePosition[] {
m_lFrontModule.getPosition(),
m_rFrontModule.getPosition(),
m_lRearModule.getPosition(),
m_rRearModule.getPosition()
};
}
/**
* Update robot pose
*/
private void updatePose() {
// Save previous pose
m_previousPose = getPose();
// Update pose based on odometry
//m_poseEstimator.update(getRotation2d(), getModulePositions());
// Update current heading
m_currentHeading = new Rotation2d(getPose().getX() - m_previousPose.getX(), getPose().getY() - m_previousPose.getY());
// Get estimated poses from VisionSubsystem
var apriltagCameraResults = VisionSubsystem.getInstance().getEstimatedGlobalPoses();
// Exit if no valid vision pose estimates
if (apriltagCameraResults.isEmpty()) return;
// Exit if robot is spinning too fast
if (getRotateRate().gt(VISION_ANGULAR_VELOCITY_THRESHOLD)) return;
// Add vision measurements to pose estimator
// for (var result : apriltagCameraResults) {
// m_poseEstimator.addVisionMeasurement(
// result.estimatedRobotPose.estimatedPose.toPose2d(),
// result.estimatedRobotPose.timestampSeconds,
// result.visionMeasurementStdDevs
// );
// }
}
/**
* Log DriveSubsystem outputs
*/
private void logOutputs() {
Logger.recordOutput(getName() + POSE_LOG_ENTRY, getPose());
Logger.recordOutput(getName() + ACTUAL_SWERVE_STATE_LOG_ENTRY, getModuleStates());
Logger.recordOutput(getName() + IS_AIMED_LOG_ENTRY, isAimed());
}
/**
* SmartDashboard indicators
*/
private void smartDashboard() {
m_field.setRobotPose(getPose());
SmartDashboard.putBoolean("TC", m_isTractionControlEnabled);
SmartDashboard.putBoolean("PurplePath", m_purplePathClient.isConnected());
SmartDashboard.putBoolean("FC", m_controlCentricity.equals(ControlCentricity.FIELD_CENTRIC));
SmartDashboard.putString("Alliance", m_currentAlliance.name());
}
/**
* Start calling this repeatedly when robot is in danger of tipping over
*/
private void antiTip() {
// Calculate direction of tip
double direction = Math.atan2(getRoll().in(Units.Degrees), getPitch().in(Units.Degrees));
// Drive to counter tipping motion
drive(
ControlCentricity.ROBOT_CENTRIC,
DRIVE_MAX_LINEAR_SPEED.divide(4).times(Math.cos(direction)),
DRIVE_MAX_LINEAR_SPEED.divide(4).times(Math.sin(direction)),
Units.DegreesPerSecond.of(0.0)
);
}
/**
* Aim robot at a desired point on the field
* @param xRequest Desired X axis (forward) speed [-1.0, +1.0]
* @param yRequest Desired Y axis (sideways) speed [-1.0, +1.0]
* @param rotateRequest Desired rotate speed (ONLY USED IF POINT IS NULL) [-1.0, +1.0]
* @param point Target point, pass in null to signify invalid point
* @param boolean True to point back of robot to target
* @param velocityCorrection True to compensate for robot's own velocity
*/
private void aimAtPoint(ControlCentricity controlCentricity, double xRequest, double yRequest, double rotateRequest, Translation2d point, boolean reversed, boolean velocityCorrection) {
// Calculate desired robot velocity
double moveRequest = Math.hypot(xRequest, yRequest);
double moveDirection = Math.atan2(yRequest, xRequest);
var velocityOutput = m_throttleMap.throttleLookup(moveRequest).negate();
// Drive normally and return if invalid point
if (point == null) {
var rotateOutput = m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest).negate();
drive(
m_controlCentricity,
velocityOutput.times(Math.cos(moveDirection)),
velocityOutput.times(Math.sin(moveDirection)),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
return;
}
// Mark PID controller being used
if (reversed) {
m_autoAimFront = false;
m_autoAimBack = true;
} else {
m_autoAimFront = true;
m_autoAimBack = false;
}
// Get current pose
Pose2d currentPose = getPose();
// Angle to target point
Rotation2d targetAngle = new Rotation2d(point.getX() - currentPose.getX(), point.getY() - currentPose.getY());
// Movement vector of robot
Vector2D robotVector = new Vector2D(velocityOutput.times(m_currentHeading.getCos()).in(Units.MetersPerSecond), velocityOutput.times(m_currentHeading.getSin()).in(Units.MetersPerSecond));
// Aim point
Translation2d aimPoint = point.minus(new Translation2d(robotVector.getX(), robotVector.getY()));
// Vector from robot to target
Vector2D targetVector = new Vector2D(currentPose.getTranslation().getDistance(point) * targetAngle.getCos(), currentPose.getTranslation().getDistance(point) * targetAngle.getSin());
// Parallel component of robot's motion to target vector
Vector2D parallelRobotVector = targetVector.scalarMultiply(robotVector.dotProduct(targetVector) / targetVector.getNormSq());
// Perpendicular component of robot's motion to target vector
Vector2D perpendicularRobotVector = robotVector.subtract(parallelRobotVector).scalarMultiply(velocityCorrection ? AIM_VELOCITY_COMPENSATION_FUDGE_FACTOR : 0.0);
// Adjust aim point using calculated vector
Translation2d adjustedPoint = point.minus(new Translation2d(perpendicularRobotVector.getX(), perpendicularRobotVector.getY()));
// Calculate new angle using adjusted point
Rotation2d adjustedAngle = new Rotation2d(adjustedPoint.getX() - currentPose.getX(), adjustedPoint.getY() - currentPose.getY());
// Calculate necessary rotate rate
var rotateOutput = reversed
? Units.DegreesPerSecond.of(m_autoAimPIDControllerBack.calculate(currentPose.getRotation().plus(GlobalConstants.ROTATION_PI).getDegrees(), adjustedAngle.getDegrees()))
: Units.DegreesPerSecond.of(m_autoAimPIDControllerFront.calculate(currentPose.getRotation().getDegrees(), adjustedAngle.getDegrees()));
// Log aim point
double aimError = currentPose.getRotation().getDegrees() - adjustedAngle.getDegrees();
Logger.recordOutput(getName() + "/AimPoint", new Pose2d(aimPoint, new Rotation2d()));
Logger.recordOutput(getName() + "/AimError", Math.copySign(((180 - Math.abs(aimError)) % 180), (aimError)));
// Drive robot accordingly
drive(
m_controlCentricity,
velocityOutput.times(Math.cos(moveDirection)),
velocityOutput.times(Math.sin(moveDirection)),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
}
/**
* Rotates the robot to the nearest cardinal direction while preserving strafing
* @param xRequest Desired X axis (forward) speed [-1.0, +1.0]
* @param yRequest Desired Y axis (sideways) speed [-1.0, +1.0]
*/
private void snapToImportantDirection(double xRequest, double yRequest) {
// Calculate desired robot velocity
double moveRequest = Math.hypot(xRequest, yRequest);
double moveDirection = Math.atan2(yRequest, xRequest);
var velocityOutput = m_throttleMap.throttleLookup(moveRequest).negate();
double sourceDistance = getPose().getTranslation().getDistance(Constants.Field.SOURCE.getGoalPose().getTranslation());
Rotation2d currentRotation = getPose().getRotation();
double desiredAngle;
if (sourceDistance < 2){
desiredAngle = m_selectedSourceDirection.in(Units.Degrees);
} else desiredAngle = m_selectedAmpDirection.in(Units.Degrees);
var rotateOutput = Units.DegreesPerSecond.of(m_autoAimPIDControllerFront.calculate(currentRotation.getDegrees(), desiredAngle));
// Drive with the pose to the snapped cardinal direction
drive(
m_controlCentricity,
velocityOutput.times(Math.cos(moveDirection)),
velocityOutput.times(Math.sin(moveDirection)),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
}
/**
* Rotates the robot to the nearest cardinal direction while preserving strafing
* @param xRequestSupplier X axis speed supplier
* @param yRequestSupplier Y axis speed supplier
* @return Command to snap to the nearest cardinal direction
*/
public Command snapToImportantDirectionCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier) {
return runEnd(
() -> snapToImportantDirection(xRequestSupplier.getAsDouble(), yRequestSupplier.getAsDouble()),
() -> resetRotatePID()
);
}
/**
*
* @param xRequest
* @param yRequest
* @param rotateRequest
*/
private void autoDefense(double xRequest, double yRequest, double rotateRequest) {
Optional<Measure<Angle>> objectYaw = VisionSubsystem.getInstance().getObjectHeading();
double moveRequest = Math.hypot(xRequest, yRequest);
double moveDirection = Math.atan2(yRequest, xRequest);
var velocityOutput = m_throttleMap.throttleLookup(moveRequest).negate();
var rotateOutput = m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest).negate();
if (objectYaw.isEmpty()) {
System.out.println(rotateOutput);
drive(
m_controlCentricity,
velocityOutput.times(Math.cos(moveDirection)),
velocityOutput.times(Math.sin(moveDirection)),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
return;
}
System.out.println("object yaw is not empy");
moveRequest = Math.hypot(xRequest, 0.0);
moveDirection = Math.atan2(0.0, xRequest);
velocityOutput = m_throttleMap.throttleLookup(moveRequest);
System.out.println(rotateOutput);
drive(
ControlCentricity.ROBOT_CENTRIC,
velocityOutput,
DRIVE_MAX_LINEAR_SPEED.times(objectYaw.get().in(Units.Degrees) / Constants.VisionHardware.CAMERA_OBJECT_FOV.getDegrees()),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
}
/**
* Aim robot by given angle
* @param angle Desired angle in degrees
*/
private void aimAtAngle(double angle) {
double rotateOutput = m_rotatePIDController.calculate(getAngle().in(Units.Degrees), getAngle().in(Units.Degrees) + angle);
drive(
m_controlCentricity,
Units.MetersPerSecond.of(0),
Units.MetersPerSecond.of(0),
Units.DegreesPerSecond.of(rotateOutput),
getInertialVelocity(),
getRotateRate()
);
}
/**
* Call this repeatedly to drive using PID during teleoperation
* @param xRequest Desired X axis (forward) speed [-1.0, +1.0]
* @param yRequest Desired Y axis (sideways) speed [-1.0, +1.0]
* @param rotateRequest Desired rotate speed [-1.0, +1.0]
*/
private void teleopPID(double xRequest, double yRequest, double rotateRequest) {
// Calculate move request and direction
double moveRequest = Math.hypot(xRequest, yRequest);
double moveDirection = Math.atan2(yRequest, xRequest);
// Get throttle and rotate output
var velocityOutput = m_throttleMap.throttleLookup(moveRequest).negate();
var rotateOutput = m_rotatePIDController.calculate(getAngle(), getRotateRate(), rotateRequest).negate();
// Update auto-aim controllers
m_autoAimPIDControllerFront.calculate(
getPose().getRotation().getDegrees(),
getPose().getRotation().getDegrees()
);
m_autoAimPIDControllerBack.calculate(
getPose().getRotation().plus(GlobalConstants.ROTATION_PI).getDegrees(),
getPose().getRotation().plus(GlobalConstants.ROTATION_PI).getDegrees()
);
m_autoAimFront = false;
m_autoAimBack = false;
// Drive robot
drive(
m_controlCentricity,
velocityOutput.times(Math.cos(moveDirection)),
velocityOutput.times(Math.sin(moveDirection)),
rotateOutput,
getInertialVelocity(),
getRotateRate()
);
}
/**
* Lock swerve modules
*/
private void lock() {
m_lFrontModule.lock();
m_rFrontModule.lock();
m_lRearModule.lock();
m_rRearModule.lock();
}
/**
* Stop robot
*/
private void stop() {
m_lFrontModule.stop();
m_rFrontModule.stop();
m_lRearModule.stop();
m_rRearModule.stop();
}
/**
* Toggle traction control
*/
private void toggleTractionControl() {
m_isTractionControlEnabled = !m_isTractionControlEnabled;
m_lFrontModule.toggleTractionControl();
m_rFrontModule.toggleTractionControl();
m_lRearModule.toggleTractionControl();
m_rRearModule.toggleTractionControl();
}
/**
* Enable traction control
*/
private void enableTractionControl() {
m_isTractionControlEnabled = true;
m_lFrontModule.enableTractionControl();
m_rFrontModule.enableTractionControl();
m_lRearModule.enableTractionControl();
m_rRearModule.enableTractionControl();
}
/**
* Disable traction control
*/
private void disableTractionControl() {
m_isTractionControlEnabled = false;
m_lFrontModule.disableTractionControl();
m_rFrontModule.disableTractionControl();
m_lRearModule.disableTractionControl();
m_rRearModule.disableTractionControl();
}
/**
* Reset pose estimator
* @param pose Pose to set robot to
*/
private void resetPose(Pose2d pose) {
m_swervePoseEstimatorService.resetPose(pose);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
// Save previous pose
m_previousPose = getPose();
// Update current heading
m_currentHeading = new Rotation2d(getPose().getX() - m_previousPose.getX(), getPose().getY() - m_previousPose.getY());
if (RobotBase.isSimulation()) return;
//updatePose();
smartDashboard();
logOutputs();
}
@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run in simulation
double randomNoise = ThreadLocalRandom.current().nextDouble(0.9, 1.0);
m_navx.getInputs().xVelocity = Units.MetersPerSecond.of(m_desiredChassisSpeeds.vxMetersPerSecond * randomNoise);
m_navx.getInputs().yVelocity = Units.MetersPerSecond.of(m_desiredChassisSpeeds.vyMetersPerSecond * randomNoise);
m_navx.getInputs().yawRate = Units.RadiansPerSecond.of(m_desiredChassisSpeeds.omegaRadiansPerSecond * randomNoise);
int yawDriftDirection = ThreadLocalRandom.current().nextDouble(1.0) < 0.5 ? -1 : +1;
double angle = m_navx.getSimAngle() - Math.toDegrees(m_desiredChassisSpeeds.omegaRadiansPerSecond * randomNoise) * GlobalConstants.ROBOT_LOOP_PERIOD
+ (NAVX2_YAW_DRIFT_RATE.in(Units.DegreesPerSecond) * GlobalConstants.ROBOT_LOOP_PERIOD * yawDriftDirection);
m_navx.setSimAngle(angle);
//updatePose();
smartDashboard();
logOutputs();
}
/**
* Configure ber auto builder
*/
public void configureAutoBuilder() {
AutoBuilder.configureHolonomic(
this::getPose,
this::resetPose,
this::getChassisSpeeds,
this::autoDrive,
m_pathFollowerConfig,
() -> {
var alliance = DriverStation.getAlliance();
if (alliance.isPresent()) return alliance.get() == DriverStation.Alliance.Red;
return false;
},
this
);
}
/**
* Set alliance
* <p>
* Must be set to correct for field oriented drive
* @param alliance alliance
*/
public void setAlliance(Alliance alliance) {
m_currentAlliance = alliance;
m_allianceCorrection = m_currentAlliance.equals(Alliance.Red) ? GlobalConstants.ROTATION_PI : GlobalConstants.ROTATION_ZERO;
if (m_currentAlliance.equals(Alliance.Red)){
m_selectedAmpDirection = RED_AMP_DIRECTION;
m_selectedSourceDirection = RED_SOURCE_DIRECTION;
} else {
m_selectedAmpDirection = BLUE_AMP_DIRECTION;
m_selectedSourceDirection = BLUE_SOURCE_DIRECTION;
}
}
public Alliance getAlliance() {
return m_currentAlliance;
}
/**
* Call this repeatedly to drive during autonomous
* @param moduleStates Calculated swerve module states
*/
public void autoDrive(ChassisSpeeds speeds) {
// Get requested chassis speeds, correcting for second order kinematics
m_desiredChassisSpeeds = AdvancedSwerveKinematics.correctForDynamics(speeds);
// Convert speeds to module states, correcting for 2nd order kinematics
SwerveModuleState[] moduleStates = m_advancedKinematics.toSwerveModuleStates(
m_desiredChassisSpeeds,
getPose().getRotation(),
ControlCentricity.ROBOT_CENTRIC
);
// Desaturate drive speeds
SwerveDriveKinematics.desaturateWheelSpeeds(moduleStates, DRIVE_MAX_LINEAR_SPEED);
// Set modules to calculated states, WITHOUT traction control
setSwerveModules(moduleStates);
// Update turn PID
m_rotatePIDController.calculate(getAngle(), getRotateRate(), 0.0);
// Update auto-aim controllers
m_autoAimPIDControllerFront.calculate(
getPose().getRotation().getDegrees(),
getPose().getRotation().getDegrees()
);
m_autoAimPIDControllerBack.calculate(
getPose().getRotation().plus(GlobalConstants.ROTATION_PI).getDegrees(),
getPose().getRotation().plus(GlobalConstants.ROTATION_PI).getDegrees()
);
}
/**
* Toggles between field centric and robot centric drive control
*/
private void toggleControlCentricity() {
if (m_controlCentricity == ControlCentricity.FIELD_CENTRIC) {
this.m_controlCentricity = ControlCentricity.ROBOT_CENTRIC;
} else {
this.m_controlCentricity = ControlCentricity.FIELD_CENTRIC;
}
}
/**
* Aim robot at desired point on the field, while strafing
* @param xRequestSupplier X axis speed supplier [-1.0, +1.0]
* @param yRequestSupplier Y axis speed supplier [-1.0, +1.0]
* @param rotateRequestSupplier Rotate speed supplier (ONLY USED IF POINT IS NULL) [-1.0, +1.0]
* @param pointSupplier Desired point supplier
* @param reversed True to point rear of robot toward point
* @param velocityCorrection True to compensate for robot's own velocity
* @return Command that will aim at point while strafing
*/
public Command aimAtPointCommand(DoubleSupplier xRequestSupplier, DoubleSupplier yRequestSupplier, DoubleSupplier rotateRequestSupplier,
Supplier<Translation2d> pointSupplier, boolean reversed, boolean velocityCorrection) {
return runEnd(
() -> aimAtPoint(
m_controlCentricity,
xRequestSupplier.getAsDouble(),
yRequestSupplier.getAsDouble(),
rotateRequestSupplier.getAsDouble(),